#include <imarker_robot_state.h>
Public Member Functions | |
IMarkerEndEffectorPtr | getEEF (const std::string &name) |
bool | getFilePath (std::string &file_path, const std::string &file_name, const std::string &subdirectory) const |
moveit::core::RobotStateConstPtr | getRobotState () |
Get a pointer to the current robot state. More... | |
moveit::core::RobotStatePtr | getRobotStateNonConst () |
moveit_visual_tools::MoveItVisualToolsPtr | getVisualTools () |
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. More... | |
bool | isStateValid (bool verbose=false) |
Return true if the currently solved IK solution is valid. More... | |
bool | loadFromFile (const std::string &file_name) |
void | publishRobotState () |
Show current state in Rviz. More... | |
bool | saveToFile () |
bool | setFromPoses (const EigenSTL::vector_Affine3d poses, const moveit::core::JointModelGroup *group) |
void | setIMarkerCallback (IMarkerCallback callback) |
Set where in the parent class the feedback should be sent. More... | |
void | setRobotState (moveit::core::RobotStatePtr state) |
Set the robot state. More... | |
void | setToCurrentState () |
Set the robot state to current in planning scene monitor. More... | |
bool | setToRandomState (double clearance=0) |
Set the robot to a random position. More... | |
~IMarkerRobotState () | |
Protected Attributes | |
std::vector< ArmData > | arm_datas_ |
rviz_visual_tools::colors | color_ = rviz_visual_tools::PURPLE |
std::vector< IMarkerEndEffectorPtr > | end_effectors_ |
std::string | file_path_ |
InteractiveMarkerServerPtr | imarker_server_ |
moveit::core::RobotStatePtr | imarker_state_ |
std::string | name_ |
std::map< std::string, IMarkerEndEffectorPtr > | name_to_eef_ |
ros::NodeHandle | nh_ |
std::ofstream | output_file_ |
std::string | package_path_ |
planning_scene_monitor::PlanningSceneMonitorPtr | psm_ |
std::size_t | refresh_rate_ = 30 |
moveit_visual_tools::MoveItVisualToolsPtr | visual_tools_ |
Friends | |
class | IMarkerEndEffector |
Definition at line 80 of file imarker_robot_state.h.
moveit_visual_tools::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 at line 53 of file imarker_robot_state.cpp.
|
inline |
Definition at line 91 of file imarker_robot_state.h.
|
inline |
Definition at line 136 of file imarker_robot_state.h.
bool moveit_visual_tools::IMarkerRobotState::getFilePath | ( | std::string & | file_path, |
const std::string & | file_name, | ||
const std::string & | subdirectory | ||
) | const |
Definition at line 247 of file imarker_robot_state.cpp.
|
inline |
Get a pointer to the current robot state.
Definition at line 104 of file imarker_robot_state.h.
|
inline |
Definition at line 108 of file imarker_robot_state.h.
moveit_visual_tools::MoveItVisualToolsPtr moveit_visual_tools::IMarkerRobotState::getVisualTools | ( | ) |
Definition at line 242 of file imarker_robot_state.cpp.
bool moveit_visual_tools::IMarkerRobotState::isStateValid | ( | bool | verbose = false | ) |
Return true if the currently solved IK solution is valid.
Definition at line 221 of file imarker_robot_state.cpp.
bool moveit_visual_tools::IMarkerRobotState::loadFromFile | ( | const std::string & | file_name | ) |
Definition at line 106 of file imarker_robot_state.cpp.
void moveit_visual_tools::IMarkerRobotState::publishRobotState | ( | ) |
Show current state in Rviz.
Definition at line 237 of file imarker_robot_state.cpp.
bool moveit_visual_tools::IMarkerRobotState::saveToFile | ( | ) |
Definition at line 129 of file imarker_robot_state.cpp.
bool moveit_visual_tools::IMarkerRobotState::setFromPoses | ( | const EigenSTL::vector_Affine3d | poses, |
const moveit::core::JointModelGroup * | group | ||
) |
Definition at line 275 of file imarker_robot_state.cpp.
void moveit_visual_tools::IMarkerRobotState::setIMarkerCallback | ( | IMarkerCallback | callback | ) |
Set where in the parent class the feedback should be sent.
Definition at line 138 of file imarker_robot_state.cpp.
void moveit_visual_tools::IMarkerRobotState::setRobotState | ( | moveit::core::RobotStatePtr | state | ) |
Set the robot state.
Definition at line 144 of file imarker_robot_state.cpp.
void moveit_visual_tools::IMarkerRobotState::setToCurrentState | ( | ) |
Set the robot state to current in planning scene monitor.
Definition at line 154 of file imarker_robot_state.cpp.
bool moveit_visual_tools::IMarkerRobotState::setToRandomState | ( | double | clearance = 0 | ) |
Set the robot to a random position.
clearance | - optional value to ensure random state is not too close to obstacles. 0 is disable |
Definition at line 168 of file imarker_robot_state.cpp.
|
friend |
Definition at line 82 of file imarker_robot_state.h.
|
protected |
Definition at line 156 of file imarker_robot_state.h.
|
protected |
Definition at line 168 of file imarker_robot_state.h.
|
protected |
Definition at line 157 of file imarker_robot_state.h.
|
protected |
Definition at line 174 of file imarker_robot_state.h.
|
protected |
Definition at line 171 of file imarker_robot_state.h.
|
protected |
Definition at line 153 of file imarker_robot_state.h.
|
protected |
Definition at line 147 of file imarker_robot_state.h.
|
protected |
Definition at line 158 of file imarker_robot_state.h.
|
protected |
Definition at line 150 of file imarker_robot_state.h.
|
protected |
Definition at line 175 of file imarker_robot_state.h.
|
protected |
Definition at line 176 of file imarker_robot_state.h.
|
protected |
Definition at line 161 of file imarker_robot_state.h.
|
protected |
Definition at line 167 of file imarker_robot_state.h.
|
protected |
Definition at line 164 of file imarker_robot_state.h.