#include <apply_planning_scene_service_capability.h>
Public Member Functions | |
ApplyPlanningSceneService () | |
virtual void | initialize () |
Public Member Functions inherited from move_group::MoveGroupCapability | |
const std::string & | getName () const |
MoveGroupCapability (const std::string &capability_name) | |
void | setContext (const MoveGroupContextPtr &context) |
virtual | ~MoveGroupCapability () |
Private Member Functions | |
bool | applyScene (moveit_msgs::ApplyPlanningScene::Request &req, moveit_msgs::ApplyPlanningScene::Response &res) |
Private Attributes | |
ros::ServiceServer | service_ |
Additional Inherited Members | |
Protected Member Functions inherited from move_group::MoveGroupCapability | |
planning_interface::MotionPlanRequest | clearRequestStartState (const planning_interface::MotionPlanRequest &request) const |
moveit_msgs::PlanningScene | clearSceneRobotState (const moveit_msgs::PlanningScene &scene) const |
void | convertToMsg (const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::RobotState &first_state_msg, std::vector< moveit_msgs::RobotTrajectory > &trajectory_msg) const |
void | convertToMsg (const robot_trajectory::RobotTrajectoryPtr &trajectory, moveit_msgs::RobotState &first_state_msg, moveit_msgs::RobotTrajectory &trajectory_msg) const |
void | convertToMsg (const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::RobotState &first_state_msg, moveit_msgs::RobotTrajectory &trajectory_msg) const |
std::string | getActionResultString (const moveit_msgs::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only) |
bool | performTransform (geometry_msgs::PoseStamped &pose_msg, const std::string &target_frame) const |
std::string | stateToStr (MoveGroupState state) const |
Protected Attributes inherited from move_group::MoveGroupCapability | |
std::string | capability_name_ |
MoveGroupContextPtr | context_ |
ros::NodeHandle | node_handle_ |
ros::NodeHandle | root_node_handle_ |
Provides the ability to update the shared planning scene with a remote blocking call using a ROS-Service
Definition at line 49 of file apply_planning_scene_service_capability.h.
move_group::ApplyPlanningSceneService::ApplyPlanningSceneService | ( | ) |
Definition at line 40 of file apply_planning_scene_service_capability.cpp.
|
private |
Definition at line 50 of file apply_planning_scene_service_capability.cpp.
|
virtual |
Implements move_group::MoveGroupCapability.
Definition at line 44 of file apply_planning_scene_service_capability.cpp.
|
private |
Definition at line 59 of file apply_planning_scene_service_capability.h.