#include <query_planners_service_capability.h>
Public Member Functions | |
virtual void | initialize () |
MoveGroupQueryPlannersService () | |
Private Member Functions | |
bool | getParams (moveit_msgs::GetPlannerParams::Request &req, moveit_msgs::GetPlannerParams::Response &res) |
bool | queryInterface (moveit_msgs::QueryPlannerInterfaces::Request &req, moveit_msgs::QueryPlannerInterfaces::Response &res) |
bool | setParams (moveit_msgs::SetPlannerParams::Request &req, moveit_msgs::SetPlannerParams::Response &res) |
Private Attributes | |
ros::ServiceServer | get_service_ |
ros::ServiceServer | query_service_ |
ros::ServiceServer | set_service_ |
Definition at line 47 of file query_planners_service_capability.h.
Definition at line 41 of file query_planners_service_capability.cpp.
bool move_group::MoveGroupQueryPlannersService::getParams | ( | moveit_msgs::GetPlannerParams::Request & | req, |
moveit_msgs::GetPlannerParams::Response & | res | ||
) | [private] |
Definition at line 72 of file query_planners_service_capability.cpp.
void move_group::MoveGroupQueryPlannersService::initialize | ( | ) | [virtual] |
Implements move_group::MoveGroupCapability.
Definition at line 45 of file query_planners_service_capability.cpp.
bool move_group::MoveGroupQueryPlannersService::queryInterface | ( | moveit_msgs::QueryPlannerInterfaces::Request & | req, |
moveit_msgs::QueryPlannerInterfaces::Response & | res | ||
) | [private] |
Definition at line 56 of file query_planners_service_capability.cpp.
bool move_group::MoveGroupQueryPlannersService::setParams | ( | moveit_msgs::SetPlannerParams::Request & | req, |
moveit_msgs::SetPlannerParams::Response & | res | ||
) | [private] |
Definition at line 103 of file query_planners_service_capability.cpp.
Definition at line 62 of file query_planners_service_capability.h.
Definition at line 61 of file query_planners_service_capability.h.
Definition at line 63 of file query_planners_service_capability.h.