move_base_to_manip.h
Go to the documentation of this file.
1 
3 // Move the base until a desired end-effector pose can be reached.
4 // Andy Zelenak, 2017
6 
7 #include <actionlib/client/simple_action_client.h> // move_base needs an action client
8 #include <actionlib/server/simple_action_server.h> // This node itself is an action server
9 #include <move_base_msgs/MoveBaseAction.h>
10 #include <move_base_to_manip/desired_poseAction.h>
12 #include "moveit_msgs/DisplayTrajectory.h"
13 #include "ros/ros.h"
14 #include "std_srvs/Empty.h"
15 #include <tf/transform_listener.h>
18 
20 
22 {
23 private:
24 
25  // Helper function to set node parameters, if they aren't defined in a launch file
26  void set_node_params();
27 
28  // Once a goal is received, start planning and moving
29  void do_motion_CB( const move_base_to_manip::desired_poseGoalConstPtr& goal );
30 
31  // Helper function to plan a Cartesian motion
32  const double cartesian_motion(const std::vector<geometry_msgs::Pose>& waypoints, moveit_msgs::RobotTrajectory& trajectory, moveit::planning_interface::MoveGroupInterface& moveGroup);
33 
37  ros::ServiceClient clear_costmaps_client_ = nh_.serviceClient<std_srvs::Empty>("/move_base/clear_costmaps");
38  ros::ServiceClient clear_octomap_client_ = nh_.serviceClient<std_srvs::Empty>("clear_octomap");
39  std_srvs::Empty empty_srv_;
40 
41 public:
42  // Constructor
43  base_planner();
44 
45 };
46 
47 #define SUCCESS false
48 #define FAILURE true
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
actionlib::SimpleActionServer< move_base_to_manip::desired_poseAction > as_
ros::ServiceClient clear_octomap_client_
std_srvs::Empty empty_srv_
const double cartesian_motion(const std::vector< geometry_msgs::Pose > &waypoints, moveit_msgs::RobotTrajectory &trajectory, moveit::planning_interface::MoveGroupInterface &moveGroup)
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
ros::NodeHandle nh_
ros::ServiceClient clear_costmaps_client_
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
moveit::planning_interface::MoveGroupInterface::Plan move_plan_
void do_motion_CB(const move_base_to_manip::desired_poseGoalConstPtr &goal)


move_base_to_manip
Author(s): Andy Zelenak, Andy Zelenak
autogenerated on Sat Jul 18 2020 03:48:17