moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
interaction.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, SRI International
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Acorn Pooley */
36
37#pragma once
38
39#include <visualization_msgs/msg/interactive_marker_feedback.hpp>
40#include <visualization_msgs/msg/interactive_marker.hpp>
41#include <interactive_markers/menu_handler.hpp>
43#include <functional>
44#include <thread>
45
46namespace moveit
47{
48namespace core
49{
50class RobotState;
51}
52} // namespace moveit
53
55{
57{
61{
62 POSITION_ARROWS = 1, // arrows to change position
63 ORIENTATION_CIRCLES = 2, // circles to change orientation
64 POSITION_SPHERE = 4, // sphere: drag to change position
65 ORIENTATION_SPHERE = 8, // sphere: drag to change orientation
66 POSITION_EEF = 16, // drag end effector to change position
67 ORIENTATION_EEF = 32, // drag end effector to change orientation
68 FIXED = 64, // keep arrow and circle axis fixed
69
77};
78} // namespace InteractionStyle
79
87typedef std::function<bool(const moveit::core::RobotState& state, visualization_msgs::msg::InteractiveMarker& marker)>
89
101typedef std::function<bool(moveit::core::RobotState& state,
102 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)>
104
114typedef std::function<bool(const moveit::core::RobotState&, geometry_msgs::msg::Pose&)> InteractiveMarkerUpdateFn;
115
119{
120 // Callback to construct interactive marker.
121 // See comment on typedef above.
123
124 // Callback to handle interactive marker feedback messages.
125 // See comment on typedef above.
127
128 // Callback to update marker pose when RobotState changes.
129 // See comment on typedef above.
131
132 // Suffix added to name of markers.
133 // Automatically generated.
135};
136
140{
142 std::string parent_group;
143
145 std::string parent_link;
146
148 std::string eef_group;
149
152
154 double size;
155};
156
160{
162 std::string connecting_link;
163
165 std::string parent_frame;
166
168 std::string joint_name;
169
171 unsigned int dof;
172
174 double size;
175};
176} // namespace robot_interaction
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
Main namespace for MoveIt.
Definition exceptions.h:43
std::function< bool(moveit::core::RobotState &state, const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &feedback)> ProcessFeedbackFn
std::function< bool(const moveit::core::RobotState &, geometry_msgs::msg::Pose &)> InteractiveMarkerUpdateFn
std::function< bool(const moveit::core::RobotState &state, visualization_msgs::msg::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
Definition interaction.h:88
double size
The size of the end effector group (diameter of enclosing sphere)
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
InteractionStyle::InteractionStyle interaction
Which degrees of freedom to enable for the end-effector.
std::string eef_group
The name of the group that defines the group joints.
std::string parent_link
The name of the link in the parent group that connects to the end-effector.
InteractiveMarkerConstructorFn construct_marker
InteractiveMarkerUpdateFn update_pose
double size
The size of the connecting link (diameter of enclosing sphere)
unsigned int dof
The type of joint disguised as the number of DOF it has. 3=PLANAR in X/Y; 6=FLOATING.
std::string parent_frame
The name of the frame that is a parent of this joint.
std::string connecting_link
The link in the robot model this joint is a parent of.
std::string joint_name
The name of the joint.