41 #include <moveit_msgs/DisplayTrajectory.h> 43 #include <moveit_msgs/GetMotionPlan.h> 47 "plan_kinematic_path";
65 bool computePlan(moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res)
67 ROS_INFO(
"Received new planning request...");
72 ompl_interface::ModelBasedPlanningContextPtr context =
81 bool result = context->solve(response);
95 moveit_msgs::DisplayTrajectory
d;
97 d.trajectory_start = mplan_res.trajectory_start;
98 d.trajectory.resize(1, mplan_res.trajectory);
105 ROS_INFO(
"Responding to planning and bechmark requests");
107 ROS_INFO(
"Publishing debug information");
121 int main(
int argc,
char** argv)
126 for (
int i = 1; i < argc; ++i)
127 if (strncmp(argv[i],
"--debug", 7) == 0)
146 ROS_ERROR(
"Planning scene not configured");
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
void displaySolution(const moveit_msgs::MotionPlanResponse &mplan_res)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_ERROR_STREAM_NAMED(name, args)
ros::ServiceServer plan_service_
ros::ServiceServer display_states_service_
static const std::string ROBOT_DESCRIPTION
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool computePlan(moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::GetMotionPlan::Response &res)
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
OMPLPlannerService(planning_scene_monitor::PlanningSceneMonitor &psm, bool debug=false)
const planning_scene::PlanningScenePtr & getPlanningScene()
ros::Publisher pub_request_
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
ompl_interface::OMPLInterface ompl_interface_
void printStatus()
Print the status of this node.
static const std::string PLANNER_SERVICE_NAME
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void startStateMonitor(const std::string &joint_states_topic=DEFAULT_JOINT_STATES_TOPIC, const std::string &attached_objects_topic=DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC)
static const std::string PLANNER_NODE_NAME
planning_scene_monitor::PlanningSceneMonitor & psm_
int main(int argc, char **argv)
const std::string response
ROSCPP_DECL void waitForShutdown()