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_Isometry3d &poses, const moveit::core::JointModelGroup *group)
 
void setIMarkerCallback (const IMarkerCallback &callback)
 Set where in the parent class the feedback should be sent. More...
 
void setRobotState (const 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 112 of file imarker_robot_state.h.

Constructor & Destructor Documentation

◆ IMarkerRobotState()

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 113 of file imarker_robot_state.cpp.

◆ ~IMarkerRobotState()

moveit_visual_tools::IMarkerRobotState::~IMarkerRobotState ( )
inline

Definition at line 123 of file imarker_robot_state.h.

Member Function Documentation

◆ getEEF()

IMarkerEndEffectorPtr moveit_visual_tools::IMarkerRobotState::getEEF ( const std::string &  name)
inline

Definition at line 168 of file imarker_robot_state.h.

◆ getFilePath()

bool moveit_visual_tools::IMarkerRobotState::getFilePath ( std::string &  file_path,
const std::string &  file_name,
const std::string &  subdirectory 
) const

Definition at line 310 of file imarker_robot_state.cpp.

◆ getRobotState()

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

Get a pointer to the current robot state.

Definition at line 136 of file imarker_robot_state.h.

◆ getRobotStateNonConst()

moveit::core::RobotStatePtr moveit_visual_tools::IMarkerRobotState::getRobotStateNonConst ( )
inline

Definition at line 140 of file imarker_robot_state.h.

◆ getVisualTools()

moveit_visual_tools::MoveItVisualToolsPtr moveit_visual_tools::IMarkerRobotState::getVisualTools ( )

Definition at line 305 of file imarker_robot_state.cpp.

◆ isStateValid()

bool moveit_visual_tools::IMarkerRobotState::isStateValid ( bool  verbose = false)

Return true if the currently solved IK solution is valid.

Definition at line 289 of file imarker_robot_state.cpp.

◆ loadFromFile()

bool moveit_visual_tools::IMarkerRobotState::loadFromFile ( const std::string &  file_name)

Definition at line 174 of file imarker_robot_state.cpp.

◆ publishRobotState()

void moveit_visual_tools::IMarkerRobotState::publishRobotState ( )

Show current state in Rviz.

Definition at line 300 of file imarker_robot_state.cpp.

◆ saveToFile()

bool moveit_visual_tools::IMarkerRobotState::saveToFile ( )

Definition at line 197 of file imarker_robot_state.cpp.

◆ setFromPoses()

bool moveit_visual_tools::IMarkerRobotState::setFromPoses ( const EigenSTL::vector_Isometry3d poses,
const moveit::core::JointModelGroup group 
)

Definition at line 338 of file imarker_robot_state.cpp.

◆ setIMarkerCallback()

void moveit_visual_tools::IMarkerRobotState::setIMarkerCallback ( const IMarkerCallback callback)

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

Definition at line 206 of file imarker_robot_state.cpp.

◆ setRobotState()

void moveit_visual_tools::IMarkerRobotState::setRobotState ( const moveit::core::RobotStatePtr &  state)

Set the robot state.

Definition at line 212 of file imarker_robot_state.cpp.

◆ setToCurrentState()

void moveit_visual_tools::IMarkerRobotState::setToCurrentState ( )

Set the robot state to current in planning scene monitor.

Definition at line 222 of file imarker_robot_state.cpp.

◆ setToRandomState()

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 236 of file imarker_robot_state.cpp.

Friends And Related Function Documentation

◆ IMarkerEndEffector

friend class IMarkerEndEffector
friend

Definition at line 114 of file imarker_robot_state.h.

Member Data Documentation

◆ arm_datas_

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

Definition at line 188 of file imarker_robot_state.h.

◆ color_

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

Definition at line 200 of file imarker_robot_state.h.

◆ end_effectors_

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

Definition at line 189 of file imarker_robot_state.h.

◆ file_path_

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

Definition at line 206 of file imarker_robot_state.h.

◆ imarker_server_

InteractiveMarkerServerPtr moveit_visual_tools::IMarkerRobotState::imarker_server_
protected

Definition at line 203 of file imarker_robot_state.h.

◆ imarker_state_

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

Definition at line 185 of file imarker_robot_state.h.

◆ name_

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

Definition at line 179 of file imarker_robot_state.h.

◆ name_to_eef_

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

Definition at line 190 of file imarker_robot_state.h.

◆ nh_

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

Definition at line 182 of file imarker_robot_state.h.

◆ output_file_

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

Definition at line 207 of file imarker_robot_state.h.

◆ package_path_

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

Definition at line 208 of file imarker_robot_state.h.

◆ psm_

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

Definition at line 193 of file imarker_robot_state.h.

◆ refresh_rate_

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

Definition at line 199 of file imarker_robot_state.h.

◆ visual_tools_

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

Definition at line 196 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 Fri May 19 2023 02:14:04