Public Member Functions | Private Member Functions | Private Attributes | List of all members
safe_teleop::SafeTrajectoryPlannerROS Class Reference

A ROS wrapper for the trajectory controller that queries the param server to construct a controller. More...

#include <safe_trajectory_planner_ros.h>

Public Member Functions

bool computeVelocityCommands (const geometry_msgs::Twist::ConstPtr &vel, geometry_msgs::Twist &cmd_vel)
 Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base. More...
 
 SafeTrajectoryPlannerROS (TFListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
 Constructs the ros wrapper. More...
 
 ~SafeTrajectoryPlannerROS ()
 Destructor for the wrapper. More...
 

Private Member Functions

bool clearCostmapsService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
 
void cmdCallback (const geometry_msgs::Twist::ConstPtr &vel)
 
double distance (double x1, double y1, double x2, double y2)
 Compute the distance between two points. More...
 
std::vector< double > loadYVels (ros::NodeHandle node)
 
void odomCallback (const nav_msgs::Odometry::ConstPtr &msg)
 
void publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub, double r, double g, double b, double a)
 Publish a plan for visualization purposes. More...
 
bool stopped ()
 Check whether the robot is stopped or not. More...
 
bool transformGlobalPlan (std::vector< geometry_msgs::PoseStamped > &transformed_plan)
 Transforms the global plan of the robot from the planner frame to the local frame. More...
 

Private Attributes

nav_msgs::Odometry base_odom_
 Used to get the velocity of the robot. More...
 
double circumscribed_radius_
 
ros::ServiceServer clear_costmaps_srv_
 
ros::Publisher cmd_pub_
 
ros::Subscriber cmd_sub_
 
costmap_2d::Costmap2D costmap_
 The costmap the controller will use. More...
 
costmap_2d::Costmap2DROScostmap_ros_
 The ROS wrapper for the costmap the controller will use. More...
 
std::string global_frame_
 The frame in which the controller will run. More...
 
double inscribed_radius_
 
ros::Publisher l_plan_pub_
 
double max_sensor_range_
 Keep track of the effective maximum range of our sensors. More...
 
double max_vel_th_
 
double min_vel_th_
 
ros::NodeHandle nh_
 
boost::recursive_mutex odom_lock_
 
ros::Subscriber odom_sub_
 
std::string robot_base_frame_
 Used as the base frame id of the robot. More...
 
double rot_stopped_velocity_
 
bool safe_backwards_
 
SafeTrajectoryPlannertc_
 The trajectory controller. More...
 
TFListenertf_
 Used for transforming point clouds. More...
 
double trans_stopped_velocity_
 
ros::Publisher u_plan_pub_
 
ros::Subscriber user_sub_
 
base_local_planner::WorldModelworld_model_
 The world model that the controller will use. More...
 

Detailed Description

A ROS wrapper for the trajectory controller that queries the param server to construct a controller.

Definition at line 52 of file safe_trajectory_planner_ros.h.

Constructor & Destructor Documentation

safe_teleop::SafeTrajectoryPlannerROS::SafeTrajectoryPlannerROS ( TFListener tf,
costmap_2d::Costmap2DROS costmap_ros 
)

Constructs the ros wrapper.

Parameters
nameThe name to give this instance of the trajectory planner
tfA pointer to a transform listener
costmapThe cost map to use for assigning costs to trajectories

Definition at line 21 of file safe_trajectory_planner_ros.cpp.

safe_teleop::SafeTrajectoryPlannerROS::~SafeTrajectoryPlannerROS ( )

Destructor for the wrapper.

Definition at line 135 of file safe_trajectory_planner_ros.cpp.

Member Function Documentation

bool safe_teleop::SafeTrajectoryPlannerROS::clearCostmapsService ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  resp 
)
private

Definition at line 310 of file safe_trajectory_planner_ros.cpp.

void safe_teleop::SafeTrajectoryPlannerROS::cmdCallback ( const geometry_msgs::Twist::ConstPtr &  vel)
private

Definition at line 164 of file safe_trajectory_planner_ros.cpp.

bool safe_teleop::SafeTrajectoryPlannerROS::computeVelocityCommands ( const geometry_msgs::Twist::ConstPtr &  vel,
geometry_msgs::Twist &  cmd_vel 
)

Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.

Parameters
velVelocity received from user
cmd_velWill be filled with the velocity command to be passed to the robot base
Returns
True if a valid trajectory was found, false otherwise

Definition at line 189 of file safe_trajectory_planner_ros.cpp.

double safe_teleop::SafeTrajectoryPlannerROS::distance ( double  x1,
double  y1,
double  x2,
double  y2 
)
private

Compute the distance between two points.

Parameters
x1The first x point
y1The first y point
x2The second x point
y2The second y point

Definition at line 150 of file safe_trajectory_planner_ros.cpp.

std::vector< double > safe_teleop::SafeTrajectoryPlannerROS::loadYVels ( ros::NodeHandle  node)
private

Definition at line 104 of file safe_trajectory_planner_ros.cpp.

void safe_teleop::SafeTrajectoryPlannerROS::odomCallback ( const nav_msgs::Odometry::ConstPtr &  msg)
private

Definition at line 154 of file safe_trajectory_planner_ros.cpp.

void safe_teleop::SafeTrajectoryPlannerROS::publishPlan ( const std::vector< geometry_msgs::PoseStamped > &  path,
const ros::Publisher pub,
double  r,
double  g,
double  b,
double  a 
)
private

Publish a plan for visualization purposes.

Definition at line 291 of file safe_trajectory_planner_ros.cpp.

bool safe_teleop::SafeTrajectoryPlannerROS::stopped ( )
private

Check whether the robot is stopped or not.

Returns
True if the robot is stopped, false otherwise

Definition at line 143 of file safe_trajectory_planner_ros.cpp.

bool safe_teleop::SafeTrajectoryPlannerROS::transformGlobalPlan ( std::vector< geometry_msgs::PoseStamped > &  transformed_plan)
private

Transforms the global plan of the robot from the planner frame to the local frame.

Parameters
transformed_planPopulated with the transformed plan

Member Data Documentation

nav_msgs::Odometry safe_teleop::SafeTrajectoryPlannerROS::base_odom_
private

Used to get the velocity of the robot.

Definition at line 119 of file safe_trajectory_planner_ros.h.

double safe_teleop::SafeTrajectoryPlannerROS::circumscribed_radius_
private

Definition at line 122 of file safe_trajectory_planner_ros.h.

ros::ServiceServer safe_teleop::SafeTrajectoryPlannerROS::clear_costmaps_srv_
private

Definition at line 130 of file safe_trajectory_planner_ros.h.

ros::Publisher safe_teleop::SafeTrajectoryPlannerROS::cmd_pub_
private

Definition at line 127 of file safe_trajectory_planner_ros.h.

ros::Subscriber safe_teleop::SafeTrajectoryPlannerROS::cmd_sub_
private

Definition at line 128 of file safe_trajectory_planner_ros.h.

costmap_2d::Costmap2D safe_teleop::SafeTrajectoryPlannerROS::costmap_
private

The costmap the controller will use.

Definition at line 115 of file safe_trajectory_planner_ros.h.

costmap_2d::Costmap2DROS* safe_teleop::SafeTrajectoryPlannerROS::costmap_ros_
private

The ROS wrapper for the costmap the controller will use.

Definition at line 114 of file safe_trajectory_planner_ros.h.

std::string safe_teleop::SafeTrajectoryPlannerROS::global_frame_
private

The frame in which the controller will run.

Definition at line 117 of file safe_trajectory_planner_ros.h.

double safe_teleop::SafeTrajectoryPlannerROS::inscribed_radius_
private

Definition at line 122 of file safe_trajectory_planner_ros.h.

ros::Publisher safe_teleop::SafeTrajectoryPlannerROS::l_plan_pub_
private

Definition at line 123 of file safe_trajectory_planner_ros.h.

double safe_teleop::SafeTrajectoryPlannerROS::max_sensor_range_
private

Keep track of the effective maximum range of our sensors.

Definition at line 118 of file safe_trajectory_planner_ros.h.

double safe_teleop::SafeTrajectoryPlannerROS::max_vel_th_
private

Definition at line 133 of file safe_trajectory_planner_ros.h.

double safe_teleop::SafeTrajectoryPlannerROS::min_vel_th_
private

Definition at line 133 of file safe_trajectory_planner_ros.h.

ros::NodeHandle safe_teleop::SafeTrajectoryPlannerROS::nh_
private

Definition at line 110 of file safe_trajectory_planner_ros.h.

boost::recursive_mutex safe_teleop::SafeTrajectoryPlannerROS::odom_lock_
private

Definition at line 132 of file safe_trajectory_planner_ros.h.

ros::Subscriber safe_teleop::SafeTrajectoryPlannerROS::odom_sub_
private

Definition at line 125 of file safe_trajectory_planner_ros.h.

std::string safe_teleop::SafeTrajectoryPlannerROS::robot_base_frame_
private

Used as the base frame id of the robot.

Definition at line 120 of file safe_trajectory_planner_ros.h.

double safe_teleop::SafeTrajectoryPlannerROS::rot_stopped_velocity_
private

Definition at line 121 of file safe_trajectory_planner_ros.h.

bool safe_teleop::SafeTrajectoryPlannerROS::safe_backwards_
private

Definition at line 134 of file safe_trajectory_planner_ros.h.

SafeTrajectoryPlanner* safe_teleop::SafeTrajectoryPlannerROS::tc_
private

The trajectory controller.

Definition at line 113 of file safe_trajectory_planner_ros.h.

TFListener* safe_teleop::SafeTrajectoryPlannerROS::tf_
private

Used for transforming point clouds.

Definition at line 116 of file safe_trajectory_planner_ros.h.

double safe_teleop::SafeTrajectoryPlannerROS::trans_stopped_velocity_
private

Definition at line 121 of file safe_trajectory_planner_ros.h.

ros::Publisher safe_teleop::SafeTrajectoryPlannerROS::u_plan_pub_
private

Definition at line 124 of file safe_trajectory_planner_ros.h.

ros::Subscriber safe_teleop::SafeTrajectoryPlannerROS::user_sub_
private

Definition at line 125 of file safe_trajectory_planner_ros.h.

base_local_planner::WorldModel* safe_teleop::SafeTrajectoryPlannerROS::world_model_
private

The world model that the controller will use.

Definition at line 112 of file safe_trajectory_planner_ros.h.


The documentation for this class was generated from the following files:


safe_teleop_base
Author(s):
autogenerated on Fri Dec 20 2019 04:00:23