Public Member Functions | |
| CurrentStateValidator (void) | |
| bool | getStateValidity (arm_navigation_msgs::GetStateValidity::Request &req, arm_navigation_msgs::GetStateValidity::Response &res) |
| void | jointStateCallback (const sensor_msgs::JointStateConstPtr &joint_state) |
| void | sendMarkersForGroup (const std::string &group) |
Protected Attributes | |
| planning_environment::CollisionModels * | collision_models_ |
| planning_environment::CollisionSpaceMonitor * | csm_ |
| ros::ServiceServer | get_state_validity_service_ |
| std::string | group_name_1_ |
| std::string | group_name_2_ |
| ros::Time | last_update_time_ |
| ros::NodeHandle | priv_handle_ |
| ros::NodeHandle | root_handle_ |
| bool | send_markers_ |
| tf::TransformListener | tf_ |
| ros::Publisher | vis_marker_array_publisher_ |
| ros::Publisher | vis_marker_publisher_ |
Definition at line 52 of file current_state_validator.cpp.
| CurrentStateValidator::CurrentStateValidator | ( | void | ) | [inline] |
Definition at line 56 of file current_state_validator.cpp.
| bool CurrentStateValidator::getStateValidity | ( | arm_navigation_msgs::GetStateValidity::Request & | req, |
| arm_navigation_msgs::GetStateValidity::Response & | res | ||
| ) | [inline] |
Definition at line 80 of file current_state_validator.cpp.
| void CurrentStateValidator::jointStateCallback | ( | const sensor_msgs::JointStateConstPtr & | joint_state | ) | [inline] |
Definition at line 201 of file current_state_validator.cpp.
| void CurrentStateValidator::sendMarkersForGroup | ( | const std::string & | group | ) | [inline] |
Definition at line 128 of file current_state_validator.cpp.
Definition at line 223 of file current_state_validator.cpp.
Definition at line 224 of file current_state_validator.cpp.
Definition at line 221 of file current_state_validator.cpp.
std::string CurrentStateValidator::group_name_1_ [protected] |
Definition at line 226 of file current_state_validator.cpp.
std::string CurrentStateValidator::group_name_2_ [protected] |
Definition at line 227 of file current_state_validator.cpp.
ros::Time CurrentStateValidator::last_update_time_ [protected] |
Definition at line 230 of file current_state_validator.cpp.
ros::NodeHandle CurrentStateValidator::priv_handle_ [protected] |
Definition at line 233 of file current_state_validator.cpp.
ros::NodeHandle CurrentStateValidator::root_handle_ [protected] |
Definition at line 232 of file current_state_validator.cpp.
bool CurrentStateValidator::send_markers_ [protected] |
Definition at line 229 of file current_state_validator.cpp.
tf::TransformListener CurrentStateValidator::tf_ [protected] |
Definition at line 238 of file current_state_validator.cpp.
Definition at line 236 of file current_state_validator.cpp.
Definition at line 235 of file current_state_validator.cpp.