39 #ifndef MOVEIT_VISUAL_TOOLS_IMARKER_ROBOT_STATE_H 40 #define MOVEIT_VISUAL_TOOLS_IMARKER_ROBOT_STATE_H 45 #include <visualization_msgs/InteractiveMarkerFeedback.h> 57 using visualization_msgs::InteractiveMarkerFeedback;
58 using visualization_msgs::InteractiveMarkerControl;
60 typedef std::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&, const Eigen::Affine3d&)>
88 IMarkerRobotState(planning_scene_monitor::PlanningSceneMonitorPtr psm,
const std::string& imarker_name,
96 bool loadFromFile(
const std::string& file_name);
101 void setIMarkerCallback(IMarkerCallback callback);
106 return imarker_state_;
110 return imarker_state_;
114 void setRobotState(moveit::core::RobotStatePtr state);
117 void setToCurrentState();
124 bool setToRandomState(
double clearance = 0);
127 bool isStateValid(
bool verbose =
false);
130 void publishRobotState();
134 bool getFilePath(std::string& file_path,
const std::string& file_name,
const std::string& subdirectory)
const;
136 IMarkerEndEffectorPtr
getEEF(
const std::string& name)
138 return name_to_eef_[name];
161 planning_scene_monitor::PlanningSceneMonitorPtr
psm_;
167 std::size_t refresh_rate_ = 30;
190 const robot_state::JointModelGroup* group,
const double* ik_solution);
193 #endif // MOVEIT_VISUAL_TOOLS_IMARKER_ROBOT_STATE_H
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d