imarker_end_effector.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016, University of Colorado, Boulder
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 Univ of Colorado 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: Dave Coleman
36  Desc: Class to encapsule a visualized robot state that can be controlled using an interactive marker
37 */
38 
39 #ifndef MOVEIT_VISUAL_TOOLS_IMARKER_END_EFFECTOR_H
40 #define MOVEIT_VISUAL_TOOLS_IMARKER_END_EFFECTOR_H
41 
42 // ROS
43 #include <ros/ros.h>
45 #include <visualization_msgs/InteractiveMarkerFeedback.h>
46 #include <visualization_msgs/InteractiveMarker.h>
48 
49 // MoveIt
51 
52 // this package
55 
56 // C++
57 #include <string>
58 #include <vector>
59 
61 {
62 using visualization_msgs::InteractiveMarkerFeedback;
63 using visualization_msgs::InteractiveMarkerControl;
64 
65 typedef std::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&, const Eigen::Affine3d&)>
67 
68 class IMarkerRobotState;
69 
71 {
72 public:
76  IMarkerEndEffector(IMarkerRobotState* imarker_parent, const std::string& imarker_name, ArmData arm_data,
78 
80  {
81  }
82 
84  void getPose(Eigen::Affine3d& pose);
85 
86  bool setPoseFromRobotState();
87 
88  void iMarkerCallback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
89 
90  void solveIK(Eigen::Affine3d& pose);
91 
93 
94  void updateIMarkerPose(const Eigen::Affine3d& pose);
95 
97 
98  void make6DofMarker(const geometry_msgs::Pose& pose);
99 
100  visualization_msgs::InteractiveMarkerControl& makeBoxControl(visualization_msgs::InteractiveMarker& msg);
101 
102  void setCollisionCheckingVerbose(bool collision_checking_verbose)
103  {
104  collision_checking_verbose_ = collision_checking_verbose;
105  }
106 
107  void setOnlyCheckSelfCollision(bool only_check_self_collision)
108  {
109  only_check_self_collision_ = only_check_self_collision;
110  }
111 
112  void setUseCollisionChecking(bool use_collision_checking)
113  {
114  use_collision_checking_ = use_collision_checking;
115  }
116 
118  {
119  imarker_callback_ = callback;
120  }
121 
123  {
124  return arm_data_.ee_link_;
125  }
126 
127 private:
128  // --------------------------------------------------------
129 
130  // The short name of this class
131  std::string name_;
132 
133  // Pointer to parent
135 
136  // State
137  moveit::core::RobotStatePtr imarker_state_;
138  Eigen::Affine3d imarker_pose_;
139 
140  // Core MoveIt components
141  planning_scene_monitor::PlanningSceneMonitorPtr psm_;
142 
143  // Visual tools
145 
146  // Settings
149 
150  // File saving
152 
153  // Interactive markers
154  // interactive_markers::MenuHandler menu_handler_;
155  visualization_msgs::InteractiveMarker int_marker_;
157  boost::mutex imarker_mutex_;
158 
160 
161  // Verbose settings
165 
166  // Hook to parent class
168 }; // end class
169 
170 // Create std pointers for this class
171 typedef std::shared_ptr<IMarkerEndEffector> IMarkerEndEffectorPtr;
172 typedef std::shared_ptr<const IMarkerEndEffector> IMarkerEndEffectorConstPtr;
173 } // namespace moveit_visual_tools
174 
175 namespace
176 {
178 bool isStateValid(const planning_scene::PlanningScene* planning_scene, bool verbose, bool only_check_self_collision,
179  moveit_visual_tools::MoveItVisualToolsPtr visual_tools_, robot_state::RobotState* state,
180  const robot_state::JointModelGroup* group, const double* ik_solution);
181 }
182 
183 #endif // MOVEIT_VISUAL_TOOLS_IMARKER_END_EFFECTOR_H
moveit_visual_tools::MoveItVisualToolsPtr visual_tools_
std::shared_ptr< const IMarkerEndEffector > IMarkerEndEffectorConstPtr
std::shared_ptr< MoveItVisualTools > MoveItVisualToolsPtr
void iMarkerCallback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
std::function< void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &, const Eigen::Affine3d &)> IMarkerCallback
visualization_msgs::InteractiveMarker int_marker_
moveit::core::RobotStatePtr imarker_state_
std::shared_ptr< IMarkerEndEffector > IMarkerEndEffectorPtr
void setCollisionCheckingVerbose(bool collision_checking_verbose)
planning_scene_monitor::PlanningSceneMonitorPtr psm_
bool verbose
const moveit::core::LinkModel * getEELink()
void setUseCollisionChecking(bool use_collision_checking)
void updateIMarkerPose(const Eigen::Affine3d &pose)
void setOnlyCheckSelfCollision(bool only_check_self_collision)
void setIMarkerCallback(IMarkerCallback callback)
I wish this struct wasn&#39;t necessary, but the SRDF does not seem to support choosing one particular li...
void getPose(Eigen::Affine3d &pose)
Get the current end effector pose.
std::shared_ptr< interactive_markers::InteractiveMarkerServer > InteractiveMarkerServerPtr
IMarkerEndEffector(IMarkerRobotState *imarker_parent, const std::string &imarker_name, ArmData arm_data, rviz_visual_tools::colors color)
Constructor.
moveit::core::LinkModel * ee_link_
visualization_msgs::InteractiveMarkerControl & makeBoxControl(visualization_msgs::InteractiveMarker &msg)
void make6DofMarker(const geometry_msgs::Pose &pose)


moveit_visual_tools
Author(s): Dave Coleman
autogenerated on Thu Jul 16 2020 03:55:17