Class IMarkerRobotState

Class Documentation

class IMarkerRobotState

Public Functions

IMarkerRobotState(rclcpp::Node::SharedPtr node, 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.

inline ~IMarkerRobotState()
bool loadFromFile(const std::string &file_name)
bool saveToFile()
void setIMarkerCallback(const IMarkerCallback &callback)

Set where in the parent class the feedback should be sent.

inline moveit::core::RobotStateConstPtr getRobotState()

Get a pointer to the current robot state.

inline moveit::core::RobotStatePtr getRobotStateNonConst()
void setRobotState(const moveit::core::RobotStatePtr &state)

Set the robot state.

void setToCurrentState()

Set the robot state to current in planning scene monitor.

bool setToRandomState(double clearance = 0)

Set the robot to a random position.

Parameters:

clearance – - optional value to ensure random state is not too close to obstacles. 0 is disable

Returns:

true on success

bool isStateValid(bool verbose = false)

Return true if the currently solved IK solution is valid.

void publishRobotState()

Show current state in Rviz.

moveit_visual_tools::MoveItVisualToolsPtr getVisualTools()
bool getFilePath(std::string &file_path, const std::string &file_name, const std::string &subdirectory) const
inline IMarkerEndEffectorPtr getEEF(const std::string &name)
bool setFromPoses(const EigenSTL::vector_Isometry3d &poses, const moveit::core::JointModelGroup *group)

Protected Attributes

std::string name_
moveit::core::RobotStatePtr imarker_state_
std::vector<ArmData> arm_datas_
std::vector<IMarkerEndEffectorPtr> end_effectors_
std::map<std::string, IMarkerEndEffectorPtr> name_to_eef_
planning_scene_monitor::PlanningSceneMonitorPtr psm_
moveit_visual_tools::MoveItVisualToolsPtr visual_tools_
std::size_t refresh_rate_ = 30
rviz_visual_tools::Colors color_ = rviz_visual_tools::PURPLE
InteractiveMarkerServerPtr imarker_server_
std::string file_path_
std::ofstream output_file_
std::string package_path_