Public Member Functions | Protected Attributes | Friends | List of all members
moveit_visual_tools::IMarkerRobotState Class Reference

#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< ArmDataarm_datas_
 
rviz_visual_tools::colors color_ = rviz_visual_tools::PURPLE
 
std::vector< IMarkerEndEffectorPtrend_effectors_
 
std::string file_path_
 
InteractiveMarkerServerPtr imarker_server_
 
moveit::core::RobotStatePtr imarker_state_
 
std::string name_
 
std::map< std::string, IMarkerEndEffectorPtrname_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
 

Detailed Description

Definition at line 80 of file imarker_robot_state.h.

Constructor & Destructor Documentation

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.

moveit_visual_tools::IMarkerRobotState::~IMarkerRobotState ( )
inline

Definition at line 91 of file imarker_robot_state.h.

Member Function Documentation

IMarkerEndEffectorPtr moveit_visual_tools::IMarkerRobotState::getEEF ( const std::string &  name)
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.

moveit::core::RobotStateConstPtr moveit_visual_tools::IMarkerRobotState::getRobotState ( )
inline

Get a pointer to the current robot state.

Definition at line 104 of file imarker_robot_state.h.

moveit::core::RobotStatePtr moveit_visual_tools::IMarkerRobotState::getRobotStateNonConst ( )
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.

Parameters
clearance- optional value to ensure random state is not too close to obstacles. 0 is disable
Returns
true on success

Definition at line 168 of file imarker_robot_state.cpp.

Friends And Related Function Documentation

friend class IMarkerEndEffector
friend

Definition at line 82 of file imarker_robot_state.h.

Member Data Documentation

std::vector<ArmData> moveit_visual_tools::IMarkerRobotState::arm_datas_
protected

Definition at line 156 of file imarker_robot_state.h.

rviz_visual_tools::colors moveit_visual_tools::IMarkerRobotState::color_ = rviz_visual_tools::PURPLE
protected

Definition at line 168 of file imarker_robot_state.h.

std::vector<IMarkerEndEffectorPtr> moveit_visual_tools::IMarkerRobotState::end_effectors_
protected

Definition at line 157 of file imarker_robot_state.h.

std::string moveit_visual_tools::IMarkerRobotState::file_path_
protected

Definition at line 174 of file imarker_robot_state.h.

InteractiveMarkerServerPtr moveit_visual_tools::IMarkerRobotState::imarker_server_
protected

Definition at line 171 of file imarker_robot_state.h.

moveit::core::RobotStatePtr moveit_visual_tools::IMarkerRobotState::imarker_state_
protected

Definition at line 153 of file imarker_robot_state.h.

std::string moveit_visual_tools::IMarkerRobotState::name_
protected

Definition at line 147 of file imarker_robot_state.h.

std::map<std::string, IMarkerEndEffectorPtr> moveit_visual_tools::IMarkerRobotState::name_to_eef_
protected

Definition at line 158 of file imarker_robot_state.h.

ros::NodeHandle moveit_visual_tools::IMarkerRobotState::nh_
protected

Definition at line 150 of file imarker_robot_state.h.

std::ofstream moveit_visual_tools::IMarkerRobotState::output_file_
protected

Definition at line 175 of file imarker_robot_state.h.

std::string moveit_visual_tools::IMarkerRobotState::package_path_
protected

Definition at line 176 of file imarker_robot_state.h.

planning_scene_monitor::PlanningSceneMonitorPtr moveit_visual_tools::IMarkerRobotState::psm_
protected

Definition at line 161 of file imarker_robot_state.h.

std::size_t moveit_visual_tools::IMarkerRobotState::refresh_rate_ = 30
protected

Definition at line 167 of file imarker_robot_state.h.

moveit_visual_tools::MoveItVisualToolsPtr moveit_visual_tools::IMarkerRobotState::visual_tools_
protected

Definition at line 164 of file imarker_robot_state.h.


The documentation for this class was generated from the following files:


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