ROS Node which responds to motion planning requests using the CHOMP algorithm. More...
#include <chomp_planner_node.h>
Public Member Functions | |
ChompPlannerNode (ros::NodeHandle node_handle) | |
Default constructor. | |
bool | filterJointTrajectory (motion_planning_msgs::FilterJointTrajectoryWithConstraints::Request &req, motion_planning_msgs::FilterJointTrajectoryWithConstraints::Response &res) |
bool | init () |
Initialize the node. | |
bool | planKinematicPath (motion_planning_msgs::GetMotionPlan::Request &req, motion_planning_msgs::GetMotionPlan::Response &res) |
Main entry point for motion planning (callback for the plan_kinematic_path service). | |
int | run () |
Runs the node. | |
virtual | ~ChompPlannerNode () |
Destructor. | |
Private Member Functions | |
void | getLimits (const trajectory_msgs::JointTrajectory &trajectory, std::vector< motion_planning_msgs::JointLimits > &limits_out) |
Private Attributes | |
ChompCollisionSpace | chomp_collision_space_ |
ChompParameters | chomp_parameters_ |
ChompRobotModel | chomp_robot_model_ |
planning_environment::CollisionModels * | collision_models_ |
ros::ServiceServer | filter_joint_trajectory_service_ |
ros::ServiceClient | filter_trajectory_client_ |
std::map< std::string, motion_planning_msgs::JointLimits > | joint_limits_ |
std::map< std::string, double > | joint_velocity_limits_ |
int | maximum_spline_points_ |
int | minimum_spline_points_ |
planning_environment::CollisionSpaceMonitor * | monitor_ |
ros::NodeHandle | node_handle_ |
ros::ServiceServer | plan_kinematic_path_service_ |
std::string | reference_frame_ |
ros::NodeHandle | root_handle_ |
tf::TransformListener | tf_ |
double | trajectory_discretization_ |
double | trajectory_duration_ |
bool | use_trajectory_filter_ |
ros::Publisher | vis_marker_array_publisher_ |
ros::Publisher | vis_marker_publisher_ |
ROS Node which responds to motion planning requests using the CHOMP algorithm.
Definition at line 59 of file chomp_planner_node.h.
chomp::ChompPlannerNode::ChompPlannerNode | ( | ros::NodeHandle | node_handle | ) |
Default constructor.
Definition at line 57 of file chomp_planner_node.cpp.
chomp::ChompPlannerNode::~ChompPlannerNode | ( | ) | [virtual] |
Destructor.
Definition at line 139 of file chomp_planner_node.cpp.
bool chomp::ChompPlannerNode::filterJointTrajectory | ( | motion_planning_msgs::FilterJointTrajectoryWithConstraints::Request & | req, | |
motion_planning_msgs::FilterJointTrajectoryWithConstraints::Response & | res | |||
) |
Definition at line 282 of file chomp_planner_node.cpp.
void chomp::ChompPlannerNode::getLimits | ( | const trajectory_msgs::JointTrajectory & | trajectory, | |
std::vector< motion_planning_msgs::JointLimits > & | limits_out | |||
) | [private] |
Definition at line 517 of file chomp_planner_node.cpp.
bool chomp::ChompPlannerNode::init | ( | ) |
Initialize the node.
Definition at line 63 of file chomp_planner_node.cpp.
bool chomp::ChompPlannerNode::planKinematicPath | ( | motion_planning_msgs::GetMotionPlan::Request & | req, | |
motion_planning_msgs::GetMotionPlan::Response & | res | |||
) |
Main entry point for motion planning (callback for the plan_kinematic_path service).
Definition at line 151 of file chomp_planner_node.cpp.
int chomp::ChompPlannerNode::run | ( | ) |
Chomp Collision space
Definition at line 100 of file chomp_planner_node.h.
Chomp Parameters
Definition at line 99 of file chomp_planner_node.h.
Chomp Robot Model
Definition at line 98 of file chomp_planner_node.h.
planning_environment::CollisionModels* chomp::ChompPlannerNode::collision_models_ [private] |
Definition at line 93 of file chomp_planner_node.h.
ros::ServiceServer chomp::ChompPlannerNode::filter_joint_trajectory_service_ [private] |
The planning service
Definition at line 91 of file chomp_planner_node.h.
ros::ServiceClient chomp::ChompPlannerNode::filter_trajectory_client_ [private] |
Definition at line 115 of file chomp_planner_node.h.
std::map<std::string, motion_planning_msgs::JointLimits> chomp::ChompPlannerNode::joint_limits_ [private] |
Definition at line 110 of file chomp_planner_node.h.
std::map<std::string, double> chomp::ChompPlannerNode::joint_velocity_limits_ [private] |
Map of joints to velocity limits
Definition at line 105 of file chomp_planner_node.h.
int chomp::ChompPlannerNode::maximum_spline_points_ [private] |
Definition at line 107 of file chomp_planner_node.h.
int chomp::ChompPlannerNode::minimum_spline_points_ [private] |
Definition at line 108 of file chomp_planner_node.h.
planning_environment::CollisionSpaceMonitor* chomp::ChompPlannerNode::monitor_ [private] |
Definition at line 94 of file chomp_planner_node.h.
ros::NodeHandle chomp::ChompPlannerNode::node_handle_ [private] |
Definition at line 88 of file chomp_planner_node.h.
ros::ServiceServer chomp::ChompPlannerNode::plan_kinematic_path_service_ [private] |
The planning service
Definition at line 89 of file chomp_planner_node.h.
std::string chomp::ChompPlannerNode::reference_frame_ [private] |
Definition at line 96 of file chomp_planner_node.h.
ros::NodeHandle chomp::ChompPlannerNode::root_handle_ [private] |
ROS Node handle
Definition at line 88 of file chomp_planner_node.h.
tf::TransformListener chomp::ChompPlannerNode::tf_ [private] |
Definition at line 95 of file chomp_planner_node.h.
double chomp::ChompPlannerNode::trajectory_discretization_ [private] |
Default discretization of the planned motion
Definition at line 102 of file chomp_planner_node.h.
double chomp::ChompPlannerNode::trajectory_duration_ [private] |
Default duration of the planned motion
Definition at line 101 of file chomp_planner_node.h.
bool chomp::ChompPlannerNode::use_trajectory_filter_ [private] |
Definition at line 106 of file chomp_planner_node.h.
ros::Publisher chomp::ChompPlannerNode::vis_marker_array_publisher_ [private] |
Publisher for marker arrays
Definition at line 103 of file chomp_planner_node.h.
ros::Publisher chomp::ChompPlannerNode::vis_marker_publisher_ [private] |
Publisher for markers
Definition at line 104 of file chomp_planner_node.h.