#include <obstacle_distance_moveit.h>
Definition at line 40 of file obstacle_distance_moveit.h.
◆ ObstacleDistanceMoveit()
| ObstacleDistanceMoveit::ObstacleDistanceMoveit |
( |
| ) |
|
◆ calculateDistanceServiceCallback()
| bool ObstacleDistanceMoveit::calculateDistanceServiceCallback |
( |
cob_control_msgs::GetObstacleDistance::Request & |
req, |
|
|
cob_control_msgs::GetObstacleDistance::Response & |
res |
|
) |
| |
|
private |
◆ calculateDistanceTimerCallback()
| void ObstacleDistanceMoveit::calculateDistanceTimerCallback |
( |
const ros::TimerEvent & |
event | ) |
|
|
private |
◆ getDistanceInfo()
| cob_control_msgs::ObstacleDistance ObstacleDistanceMoveit::getDistanceInfo |
( |
const std::shared_ptr< fcl::CollisionObject > |
object_a, |
|
|
const std::shared_ptr< fcl::CollisionObject > |
object_b |
|
) |
| |
|
private |
◆ planningSceneCallback()
| bool ObstacleDistanceMoveit::planningSceneCallback |
( |
moveit_msgs::GetPlanningScene::Request & |
req, |
|
|
moveit_msgs::GetPlanningScene::Response & |
res |
|
) |
| |
|
private |
◆ planningSceneTimerCallback()
| void ObstacleDistanceMoveit::planningSceneTimerCallback |
( |
const ros::TimerEvent & |
event | ) |
|
|
private |
◆ registerCallback()
| bool ObstacleDistanceMoveit::registerCallback |
( |
cob_srvs::SetString::Request & |
req, |
|
|
cob_srvs::SetString::Response & |
res |
|
) |
| |
|
private |
◆ unregisterCallback()
| bool ObstacleDistanceMoveit::unregisterCallback |
( |
cob_srvs::SetString::Request & |
req, |
|
|
cob_srvs::SetString::Response & |
res |
|
) |
| |
|
private |
◆ updatedScene()
◆ acm_
◆ calculate_obstacle_distance_
◆ collision_objects_
| std::map<std::string, std::shared_ptr<fcl::CollisionObject> > ObstacleDistanceMoveit::collision_objects_ |
|
private |
◆ distance_pub_
◆ distance_timer_
| ros::Timer ObstacleDistanceMoveit::distance_timer_ |
|
private |
◆ MAXIMAL_MINIMAL_DISTANCE
| float ObstacleDistanceMoveit::MAXIMAL_MINIMAL_DISTANCE |
|
private |
◆ monitored_scene_pub_
◆ monitored_scene_server_
◆ nh_
◆ planning_scene_monitor_
| planning_scene_monitor::PlanningSceneMonitorPtr ObstacleDistanceMoveit::planning_scene_monitor_ |
|
private |
◆ planning_scene_timer_
| ros::Timer ObstacleDistanceMoveit::planning_scene_timer_ |
|
private |
◆ register_server_
◆ registered_links_
◆ registered_links_mutex_
| boost::mutex ObstacleDistanceMoveit::registered_links_mutex_ |
|
private |
◆ robot_links_
| std::map<std::string, std::shared_ptr<fcl::CollisionObject> > ObstacleDistanceMoveit::robot_links_ |
|
private |
◆ unregister_server_
The documentation for this class was generated from the following files: