imarker_robot_state.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_ROBOT_STATE_H
40 #define MOVEIT_VISUAL_TOOLS_IMARKER_ROBOT_STATE_H
41 
42 // ROS
43 #include <ros/ros.h>
45 #include <visualization_msgs/InteractiveMarkerFeedback.h>
46 
47 // MoveIt
50 
51 // C++
52 #include <string>
53 #include <vector>
54 
55 namespace moveit_visual_tools
56 {
57 using visualization_msgs::InteractiveMarkerControl;
58 using visualization_msgs::InteractiveMarkerFeedback;
59 
60 typedef std::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&, const Eigen::Isometry3d&)>
62 
63 typedef std::shared_ptr<interactive_markers::InteractiveMarkerServer> InteractiveMarkerServerPtr;
64 
65 class IMarkerEndEffector;
66 typedef std::shared_ptr<IMarkerEndEffector> IMarkerEndEffectorPtr;
67 typedef std::shared_ptr<const IMarkerEndEffector> IMarkerEndEffectorConstPtr;
68 
72 struct ArmData
73 {
75 
78 };
79 
80 class IMarkerRobotState
81 {
82  friend class IMarkerEndEffector;
83 
84 public:
88  IMarkerRobotState(planning_scene_monitor::PlanningSceneMonitorPtr psm, const std::string& imarker_name,
89  std::vector<ArmData> arm_datas, rviz_visual_tools::colors color, const std::string& package_path);
90 
92  {
93  output_file_.close();
94  }
95 
96  bool loadFromFile(const std::string& file_name);
97 
98  bool saveToFile();
99 
101  void setIMarkerCallback(const IMarkerCallback& callback);
102 
104  moveit::core::RobotStateConstPtr getRobotState()
105  {
107  }
108  moveit::core::RobotStatePtr getRobotStateNonConst()
109  {
110  return imarker_state_;
111  }
112 
114  void setRobotState(const moveit::core::RobotStatePtr& state);
115 
117  void setToCurrentState();
118 
124  bool setToRandomState(double clearance = 0);
125 
127  bool isStateValid(bool verbose = false);
128 
130  void publishRobotState();
131 
133 
134  bool getFilePath(std::string& file_path, const std::string& file_name, const std::string& subdirectory) const;
135 
136  IMarkerEndEffectorPtr getEEF(const std::string& name)
137  {
138  return name_to_eef_[name];
139  }
140 
142 
143 protected:
144  // --------------------------------------------------------
145 
146  // The short name of this class
147  std::string name_;
148 
149  // A shared node handle
151 
152  // State
153  moveit::core::RobotStatePtr imarker_state_;
154 
155  // End effectors
156  std::vector<ArmData> arm_datas_;
157  std::vector<IMarkerEndEffectorPtr> end_effectors_;
158  std::map<std::string, IMarkerEndEffectorPtr> name_to_eef_;
159 
160  // Core MoveIt components
161  planning_scene_monitor::PlanningSceneMonitorPtr psm_;
162 
163  // Visual tools
165 
166  // Settings
167  std::size_t refresh_rate_ = 30;
169 
170  // Interactive markers
172 
173  // File saving
174  std::string file_path_;
175  std::ofstream output_file_;
176  std::string package_path_; // File location of this package
177 
178 }; // end class
179 
180 // Create std pointers for this class
181 typedef std::shared_ptr<IMarkerRobotState> IMarkerRobotStatePtr;
182 typedef std::shared_ptr<const IMarkerRobotState> IMarkerRobotStateConstPtr;
183 } // namespace moveit_visual_tools
184 
185 #endif // MOVEIT_VISUAL_TOOLS_IMARKER_ROBOT_STATE_H
moveit::core::LinkModel
moveit_visual_tools::IMarkerRobotState::isStateValid
bool isStateValid(bool verbose=false)
Return true if the currently solved IK solution is valid.
Definition: imarker_robot_state.cpp:289
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
moveit_visual_tools::IMarkerRobotState::setToCurrentState
void setToCurrentState()
Set the robot state to current in planning scene monitor.
Definition: imarker_robot_state.cpp:222
moveit_visual_tools::IMarkerRobotState::setFromPoses
bool setFromPoses(const EigenSTL::vector_Isometry3d &poses, const moveit::core::JointModelGroup *group)
Definition: imarker_robot_state.cpp:338
moveit_visual_tools::IMarkerEndEffectorPtr
std::shared_ptr< IMarkerEndEffector > IMarkerEndEffectorPtr
Definition: imarker_end_effector.h:208
moveit_visual_tools::IMarkerRobotState::getRobotState
moveit::core::RobotStateConstPtr getRobotState()
Get a pointer to the current robot state.
Definition: imarker_robot_state.h:136
moveit_visual_tools::IMarkerRobotStateConstPtr
std::shared_ptr< const IMarkerRobotState > IMarkerRobotStateConstPtr
Definition: imarker_robot_state.h:214
ros.h
moveit_visual_tools::ArmData::jmg_
moveit::core::JointModelGroup * jmg_
Definition: imarker_robot_state.h:106
moveit_visual_tools::ArmData::ee_link_
moveit::core::LinkModel * ee_link_
Definition: imarker_robot_state.h:109
moveit_visual_tools::IMarkerRobotState::arm_datas_
std::vector< ArmData > arm_datas_
Definition: imarker_robot_state.h:188
moveit_visual_tools::IMarkerRobotState::IMarkerRobotState
IMarkerRobotState(planning_scene_monitor::PlanningSceneMonitorPtr psm, const std::string &imarker_name, std::vector< ArmData > arm_datas, rviz_visual_tools::colors color, const std::string &package_path)
Constructor.
Definition: imarker_robot_state.cpp:113
moveit_visual_tools::ArmData::ArmData
ArmData(moveit::core::JointModelGroup *jmg, moveit::core::LinkModel *ee_link)
Definition: imarker_robot_state.h:106
moveit_visual_tools::IMarkerRobotState::imarker_state_
moveit::core::RobotStatePtr imarker_state_
Definition: imarker_robot_state.h:185
moveit_visual_tools::IMarkerRobotState::end_effectors_
std::vector< IMarkerEndEffectorPtr > end_effectors_
Definition: imarker_robot_state.h:189
moveit_visual_tools::IMarkerRobotState::getFilePath
bool getFilePath(std::string &file_path, const std::string &file_name, const std::string &subdirectory) const
Definition: imarker_robot_state.cpp:310
moveit_visual_tools::IMarkerRobotState::~IMarkerRobotState
~IMarkerRobotState()
Definition: imarker_robot_state.h:123
robot_state.h
rviz_visual_tools::PURPLE
PURPLE
moveit_visual_tools::IMarkerRobotState::getRobotStateNonConst
moveit::core::RobotStatePtr getRobotStateNonConst()
Definition: imarker_robot_state.h:140
moveit_visual_tools::IMarkerRobotState::color_
rviz_visual_tools::colors color_
Definition: imarker_robot_state.h:200
moveit_visual_tools::IMarkerRobotState::getEEF
IMarkerEndEffectorPtr getEEF(const std::string &name)
Definition: imarker_robot_state.h:168
moveit_visual_tools::IMarkerRobotState::psm_
planning_scene_monitor::PlanningSceneMonitorPtr psm_
Definition: imarker_robot_state.h:193
moveit_visual_tools::IMarkerEndEffectorConstPtr
std::shared_ptr< const IMarkerEndEffector > IMarkerEndEffectorConstPtr
Definition: imarker_end_effector.h:209
moveit_visual_tools::IMarkerRobotState::nh_
ros::NodeHandle nh_
Definition: imarker_robot_state.h:182
moveit_visual_tools::IMarkerRobotState::name_to_eef_
std::map< std::string, IMarkerEndEffectorPtr > name_to_eef_
Definition: imarker_robot_state.h:190
moveit_visual_tools::MoveItVisualToolsPtr
std::shared_ptr< MoveItVisualTools > MoveItVisualToolsPtr
Definition: moveit_visual_tools.h:782
name
std::string name
moveit_visual_tools::IMarkerRobotStatePtr
std::shared_ptr< IMarkerRobotState > IMarkerRobotStatePtr
Definition: imarker_robot_state.h:213
moveit_visual_tools::IMarkerRobotState::setRobotState
void setRobotState(const moveit::core::RobotStatePtr &state)
Set the robot state.
Definition: imarker_robot_state.cpp:212
moveit_visual_tools::IMarkerRobotState::visual_tools_
moveit_visual_tools::MoveItVisualToolsPtr visual_tools_
Definition: imarker_robot_state.h:196
moveit_visual_tools::IMarkerRobotState::setIMarkerCallback
void setIMarkerCallback(const IMarkerCallback &callback)
Set where in the parent class the feedback should be sent.
Definition: imarker_robot_state.cpp:206
moveit_visual_tools::IMarkerRobotState::IMarkerEndEffector
friend class IMarkerEndEffector
Definition: imarker_robot_state.h:114
moveit_visual_tools::IMarkerCallback
std::function< void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &, const Eigen::Isometry3d &)> IMarkerCallback
Definition: imarker_end_effector.h:100
moveit_visual_tools::IMarkerRobotState::getVisualTools
moveit_visual_tools::MoveItVisualToolsPtr getVisualTools()
Definition: imarker_robot_state.cpp:305
rviz_visual_tools::colors
colors
moveit_visual_tools::IMarkerRobotState::package_path_
std::string package_path_
Definition: imarker_robot_state.h:208
moveit_visual_tools::IMarkerRobotState::publishRobotState
void publishRobotState()
Show current state in Rviz.
Definition: imarker_robot_state.cpp:300
moveit_visual_tools::IMarkerRobotState::name_
std::string name_
Definition: imarker_robot_state.h:179
interactive_marker_server.h
moveit_visual_tools::IMarkerRobotState::file_path_
std::string file_path_
Definition: imarker_robot_state.h:206
moveit::core::JointModelGroup
moveit_visual_tools::IMarkerRobotState::saveToFile
bool saveToFile()
Definition: imarker_robot_state.cpp:197
moveit_visual_tools::IMarkerRobotState::imarker_server_
InteractiveMarkerServerPtr imarker_server_
Definition: imarker_robot_state.h:203
moveit_visual_tools::IMarkerRobotState::output_file_
std::ofstream output_file_
Definition: imarker_robot_state.h:207
moveit_visual_tools::IMarkerRobotState::refresh_rate_
std::size_t refresh_rate_
Definition: imarker_robot_state.h:199
moveit_visual_tools::IMarkerRobotState::setToRandomState
bool setToRandomState(double clearance=0)
Set the robot to a random position.
Definition: imarker_robot_state.cpp:236
moveit_visual_tools.h
moveit_visual_tools
Definition: imarker_end_effector.h:62
moveit_visual_tools::IMarkerRobotState::loadFromFile
bool loadFromFile(const std::string &file_name)
Definition: imarker_robot_state.cpp:174
moveit_visual_tools::InteractiveMarkerServerPtr
std::shared_ptr< interactive_markers::InteractiveMarkerServer > InteractiveMarkerServerPtr
Definition: imarker_robot_state.h:95
ros::NodeHandle


moveit_visual_tools
Author(s): Dave Coleman
autogenerated on Fri May 19 2023 02:14:04