Computes control velocities for a robot given a costmap, a plan, and the robot's position in the world. More...
#include <anti_collision_base_controller.h>
Public Member Functions | |
| AntiCollisionBaseController () | |
| Constructs an anti-collision base controller. | |
| void | joyCallBack (const geometry_msgs::TwistConstPtr &msg) |
| void | odomCallback (const nav_msgs::OdometryConstPtr &msg) |
| void | spin () |
| ~AntiCollisionBaseController () | |
| Destructs a trajectory controller. | |
Public Attributes | |
| tf::TransformListener | tf_ |
Private Member Functions | |
| double | computeNewThetaPosition (double thetai, double vth, double dt) |
| Compute orientation based on velocity. | |
| double | computeNewVelocity (double vg, double vi, double a_max, double dt) |
| Compute velocity based on acceleration. | |
| double | computeNewXPosition (double xi, double vx, double vy, double theta, double dt) |
| Compute x position based on velocity. | |
| double | computeNewYPosition (double yi, double vx, double vy, double theta, double dt) |
| Compute y position based on velocity. | |
| void | computeSafeVelocity (double x, double y, double theta, double vx_current, double vy_current, double vtheta_current, double vx_desired, double vy_desired, double vtheta_desired, double &vx_result, double &vy_result, double &vtheta_result) |
| double | footprintCost (double x_i, double y_i, double theta_i) |
| Checks the legality of the robot footprint at a position and orientation using the world model. | |
| bool | generateTrajectory (double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y, double acc_theta, base_local_planner::Trajectory &traj, double sim_time_local) |
| Generate and scor7e a single trajectory. | |
| bool | getRobotPose (double &x, double &y, double &theta) |
Private Attributes | |
| double | acc_lim_theta_ |
| The acceleration limits of the robot. | |
| double | acc_lim_x_ |
| double | acc_lim_y_ |
| ros::Publisher | base_cmd_pub_ |
| A publisher for base commands. | |
| geometry_msgs::Twist | base_odom_ |
| boost::mutex | base_odom_mutex_ |
| double | circumscribed_radius_ |
| double | controller_frequency_ |
| costmap_2d::Costmap2D | costmap_ |
| Provides access to cost map information. | |
| costmap_2d::Costmap2DROS * | costmap_ros_ |
| std::vector< geometry_msgs::Point > | footprint_spec_ |
| The footprint specification of the robot. | |
| std::string | global_frame_ |
| double | inflation_radius_ |
| The inscribed and circumscribed radii of the robot. | |
| double | inscribed_radius_ |
| ros::Subscriber | joy_sub_ |
| A subscriber for commands from the joystick. | |
| ros::Time | last_cmd_received_ |
| double | max_vel_th_ |
| double | max_vel_x_ |
| double | min_in_place_vel_th_ |
| Velocity limits for the controller. | |
| double | min_vel_cmd_theta_ |
| double | min_vel_cmd_x_ |
| double | min_vel_cmd_y_ |
| double | min_vel_th_ |
| double | min_vel_x_ |
| ros::Subscriber | odom_sub_ |
| A subscriber for odometry messages. | |
| std::string | robot_base_frame_ |
| ros::NodeHandle | ros_node_ |
| A node handle to the ROS node. | |
| double | sim_granularity_ |
| The distance between simulation points. | |
| double | sim_time_ |
| The number of seconds each trajectory is "rolled-out". | |
| trajectory::Trajectory * | sim_trajectory_ |
| double | timeout_ |
| geometry_msgs::Twist | vel_desired_ |
| boost::mutex | vel_desired_mutex_ |
| int | vtheta_samples_ |
| The number of samples we'll take in the theta dimension of the control space. | |
| int | vx_samples_ |
| The number of samples we'll take in the x dimenstion of the control space. | |
| base_local_planner::WorldModel * | world_model_ |
| The world model that the controller will use. | |
Computes control velocities for a robot given a costmap, a plan, and the robot's position in the world.
Definition at line 70 of file anti_collision_base_controller.h.
| anti_collision_base_controller::AntiCollisionBaseController::AntiCollisionBaseController | ( | ) |
Constructs an anti-collision base controller.
Definition at line 46 of file anti_collision_base_controller.cpp.
| anti_collision_base_controller::AntiCollisionBaseController::~AntiCollisionBaseController | ( | ) |
Destructs a trajectory controller.
Definition at line 113 of file anti_collision_base_controller.cpp.
| double anti_collision_base_controller::AntiCollisionBaseController::computeNewThetaPosition | ( | double | thetai, | |
| double | vth, | |||
| double | dt | |||
| ) | [inline, private] |
Compute orientation based on velocity.
| thetai | The current orientation | |
| vth | The current theta velocity | |
| dt | The timestep to take |
Definition at line 176 of file anti_collision_base_controller.h.
| double anti_collision_base_controller::AntiCollisionBaseController::computeNewVelocity | ( | double | vg, | |
| double | vi, | |||
| double | a_max, | |||
| double | dt | |||
| ) | [inline, private] |
Compute velocity based on acceleration.
| vg | The desired velocity, what we're accelerating up to | |
| vi | The current velocity | |
| a_max | An acceleration limit | |
| dt | The timestep to take |
Definition at line 189 of file anti_collision_base_controller.h.
| double anti_collision_base_controller::AntiCollisionBaseController::computeNewXPosition | ( | double | xi, | |
| double | vx, | |||
| double | vy, | |||
| double | theta, | |||
| double | dt | |||
| ) | [inline, private] |
Compute x position based on velocity.
| xi | The current x position | |
| vx | The current x velocity | |
| vy | The current y velocity | |
| theta | The current orientation | |
| dt | The timestep to take |
Definition at line 152 of file anti_collision_base_controller.h.
| double anti_collision_base_controller::AntiCollisionBaseController::computeNewYPosition | ( | double | yi, | |
| double | vx, | |||
| double | vy, | |||
| double | theta, | |||
| double | dt | |||
| ) | [inline, private] |
Compute y position based on velocity.
| yi | The current y position | |
| vx | The current x velocity | |
| vy | The current y velocity | |
| theta | The current orientation | |
| dt | The timestep to take |
Definition at line 165 of file anti_collision_base_controller.h.
| void anti_collision_base_controller::AntiCollisionBaseController::computeSafeVelocity | ( | double | x, | |
| double | y, | |||
| double | theta, | |||
| double | vx_current, | |||
| double | vy_current, | |||
| double | vtheta_current, | |||
| double | vx_desired, | |||
| double | vy_desired, | |||
| double | vtheta_desired, | |||
| double & | vx_result, | |||
| double & | vy_result, | |||
| double & | vtheta_result | |||
| ) | [private] |
Definition at line 264 of file anti_collision_base_controller.cpp.
| double anti_collision_base_controller::AntiCollisionBaseController::footprintCost | ( | double | x_i, | |
| double | y_i, | |||
| double | theta_i | |||
| ) | [private] |
Checks the legality of the robot footprint at a position and orientation using the world model.
| x_i | The x position of the robot | |
| y_i | The y position of the robot | |
| theta_i | The orientation of the robot |
Definition at line 237 of file anti_collision_base_controller.cpp.
| bool anti_collision_base_controller::AntiCollisionBaseController::generateTrajectory | ( | double | x, | |
| double | y, | |||
| double | theta, | |||
| double | vx, | |||
| double | vy, | |||
| double | vtheta, | |||
| double | vx_samp, | |||
| double | vy_samp, | |||
| double | vtheta_samp, | |||
| double | acc_x, | |||
| double | acc_y, | |||
| double | acc_theta, | |||
| base_local_planner::Trajectory & | traj, | |||
| double | sim_time_local | |||
| ) | [private] |
Generate and scor7e a single trajectory.
| x | The x position of the robot | |
| y | The y position of the robot | |
| theta | The orientation of the robot | |
| vx | The x velocity of the robot | |
| vy | The y velocity of the robot | |
| vtheta | The theta velocity of the robot | |
| vx_samp | The x velocity used to seed the trajectory | |
| vy_samp | The y velocity used to seed the trajectory | |
| vtheta_samp | The theta velocity used to seed the trajectory | |
| acc_x | The x acceleration limit of the robot | |
| acc_y | The y acceleration limit of the robot | |
| acc_theta | The theta acceleration limit of the robot | |
| traj | Will be set to the generated trajectory with its associated score | |
| sim_time_local | The time to simulate forward for |
Definition at line 119 of file anti_collision_base_controller.cpp.
| bool anti_collision_base_controller::AntiCollisionBaseController::getRobotPose | ( | double & | x, | |
| double & | y, | |||
| double & | theta | |||
| ) | [private] |
Definition at line 335 of file anti_collision_base_controller.cpp.
| void anti_collision_base_controller::AntiCollisionBaseController::joyCallBack | ( | const geometry_msgs::TwistConstPtr & | msg | ) |
| void anti_collision_base_controller::AntiCollisionBaseController::odomCallback | ( | const nav_msgs::OdometryConstPtr & | msg | ) |
Definition at line 309 of file anti_collision_base_controller.cpp.
| void anti_collision_base_controller::AntiCollisionBaseController::spin | ( | ) |
Definition at line 350 of file anti_collision_base_controller.cpp.
The acceleration limits of the robot.
Definition at line 135 of file anti_collision_base_controller.h.
Definition at line 135 of file anti_collision_base_controller.h.
Definition at line 135 of file anti_collision_base_controller.h.
ros::Publisher anti_collision_base_controller::AntiCollisionBaseController::base_cmd_pub_ [private] |
A publisher for base commands.
Definition at line 197 of file anti_collision_base_controller.h.
geometry_msgs::Twist anti_collision_base_controller::AntiCollisionBaseController::base_odom_ [private] |
Definition at line 209 of file anti_collision_base_controller.h.
boost::mutex anti_collision_base_controller::AntiCollisionBaseController::base_odom_mutex_ [private] |
Definition at line 210 of file anti_collision_base_controller.h.
Definition at line 128 of file anti_collision_base_controller.h.
Definition at line 139 of file anti_collision_base_controller.h.
costmap_2d::Costmap2D anti_collision_base_controller::AntiCollisionBaseController::costmap_ [private] |
Provides access to cost map information.
Definition at line 124 of file anti_collision_base_controller.h.
costmap_2d::Costmap2DROS* anti_collision_base_controller::AntiCollisionBaseController::costmap_ros_ [private] |
Definition at line 207 of file anti_collision_base_controller.h.
std::vector<geometry_msgs::Point> anti_collision_base_controller::AntiCollisionBaseController::footprint_spec_ [private] |
The footprint specification of the robot.
Definition at line 126 of file anti_collision_base_controller.h.
std::string anti_collision_base_controller::AntiCollisionBaseController::global_frame_ [private] |
Definition at line 141 of file anti_collision_base_controller.h.
The inscribed and circumscribed radii of the robot.
Definition at line 128 of file anti_collision_base_controller.h.
Definition at line 128 of file anti_collision_base_controller.h.
ros::Subscriber anti_collision_base_controller::AntiCollisionBaseController::joy_sub_ [private] |
A subscriber for commands from the joystick.
Definition at line 201 of file anti_collision_base_controller.h.
ros::Time anti_collision_base_controller::AntiCollisionBaseController::last_cmd_received_ [private] |
Definition at line 214 of file anti_collision_base_controller.h.
Definition at line 137 of file anti_collision_base_controller.h.
Definition at line 137 of file anti_collision_base_controller.h.
Velocity limits for the controller.
Definition at line 137 of file anti_collision_base_controller.h.
Definition at line 217 of file anti_collision_base_controller.h.
Definition at line 217 of file anti_collision_base_controller.h.
Definition at line 217 of file anti_collision_base_controller.h.
Definition at line 137 of file anti_collision_base_controller.h.
Definition at line 137 of file anti_collision_base_controller.h.
ros::Subscriber anti_collision_base_controller::AntiCollisionBaseController::odom_sub_ [private] |
A subscriber for odometry messages.
Definition at line 203 of file anti_collision_base_controller.h.
std::string anti_collision_base_controller::AntiCollisionBaseController::robot_base_frame_ [private] |
Definition at line 141 of file anti_collision_base_controller.h.
ros::NodeHandle anti_collision_base_controller::AntiCollisionBaseController::ros_node_ [private] |
A node handle to the ROS node.
Definition at line 199 of file anti_collision_base_controller.h.
The distance between simulation points.
Definition at line 131 of file anti_collision_base_controller.h.
The number of seconds each trajectory is "rolled-out".
Definition at line 130 of file anti_collision_base_controller.h.
trajectory::Trajectory* anti_collision_base_controller::AntiCollisionBaseController::sim_trajectory_ [private] |
Definition at line 219 of file anti_collision_base_controller.h.
| tf::TransformListener anti_collision_base_controller::AntiCollisionBaseController::tf_ |
Definition at line 83 of file anti_collision_base_controller.h.
Definition at line 216 of file anti_collision_base_controller.h.
geometry_msgs::Twist anti_collision_base_controller::AntiCollisionBaseController::vel_desired_ [private] |
Definition at line 209 of file anti_collision_base_controller.h.
boost::mutex anti_collision_base_controller::AntiCollisionBaseController::vel_desired_mutex_ [private] |
Definition at line 210 of file anti_collision_base_controller.h.
The number of samples we'll take in the theta dimension of the control space.
Definition at line 134 of file anti_collision_base_controller.h.
The number of samples we'll take in the x dimenstion of the control space.
Definition at line 133 of file anti_collision_base_controller.h.
base_local_planner::WorldModel* anti_collision_base_controller::AntiCollisionBaseController::world_model_ [private] |
The world model that the controller will use.
Definition at line 195 of file anti_collision_base_controller.h.