#include <base_controller.h>
Public Member Functions | |
BaseController () | |
Constructor for BaseController. | |
virtual bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
Initializes the BaseController. | |
virtual void | starting () |
Sets the position and velocity for all wheel joints. Also sets the time_of_last_cycle_ to the current robot time. | |
virtual void | stopping () |
Stops the thread. | |
virtual void | update () |
Updates the effort on all base joints. Also checks if the robot is standing still and takes appropriate action. | |
~BaseController () | |
Deconstructor for BaseController. | |
Private Member Functions | |
geometry_msgs::Twist | interpolateCommand (const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT) |
Uses the last command received to determine a sensible current command velocity. | |
void | VelCallback (const geometry_msgs::Twist::ConstPtr &msg) |
Handles incoming /cmd_vel messages. | |
Private Attributes | |
pr2_mechanism_model::RobotState * | robot_ |
pointer to the robot | |
double | timeout_ |
maximum time between commands before controller resets the (reference) velocity | |
ros::Subscriber | vel_sub |
pr2_mechanism_model::JointState * | wheel_inner_left_front_state |
pr2_mechanism_model::JointState * | wheel_inner_left_rear_state |
pr2_mechanism_model::JointState * | wheel_inner_right_front_state |
pr2_mechanism_model::JointState * | wheel_inner_right_rear_state |
double | current_pos_x |
double | current_pos_y |
double | current_pos_phi |
double | desired_pos_x |
double | desired_pos_y |
double | desired_pos_phi |
double | trans_vel_min |
double | rot_vel_min |
double | Kp_x |
double | Kd_x |
double | Kp_y |
double | Kd_y |
double | Kp_phi |
double | Kd_phi |
double | mass_x |
double | mass_y |
double | inertia_phi |
double | damping_x |
double | damping_y |
double | damping_phi |
double | u_x_max |
double | u_y_max |
double | u_phi_max |
double | max_translational_velocity_ |
double | max_rotational_velocity_ |
geometry_msgs::Twist | cmd_vel_ |
geometry_msgs::Twist | ref_vel_last_ |
geometry_msgs::Twist | max_accel_ |
ros::Time | time_of_last_cycle_ |
ros::Time | cmd_received_timestamp_ |
ros::Time | current_time |
Definition at line 59 of file base_controller.h.
Constructor for BaseController.
Definition at line 64 of file base_controller.cpp.
Deconstructor for BaseController.
Definition at line 81 of file base_controller.cpp.
bool BaseController::init | ( | pr2_mechanism_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Initializes the BaseController.
Copies all variable values from the parameter server. Also subscribes to /cmd_vel topic.
robot | pointer to the robot |
n | the handler for this nodes subscriptions |
Implements pr2_controller_interface::Controller.
Definition at line 84 of file base_controller.cpp.
geometry_msgs::Twist BaseController::interpolateCommand | ( | const geometry_msgs::Twist & | start, |
const geometry_msgs::Twist & | end, | ||
const geometry_msgs::Twist & | max_rate, | ||
const double & | dT | ||
) | [private] |
Uses the last command received to determine a sensible current command velocity.
Determines a sensible current command velocity based on the last command received, the current velocity and the desired velocity and the allowed acceleration.
start | is the last command velocity used |
end | is the desired velocity |
max_rate | is the maximum acceleration |
dT | is the time passed since the last command velocity was used |
Definition at line 347 of file base_controller.cpp.
void BaseController::starting | ( | ) | [virtual] |
Sets the position and velocity for all wheel joints. Also sets the time_of_last_cycle_ to the current robot time.
Reimplemented from pr2_controller_interface::Controller.
Definition at line 190 of file base_controller.cpp.
void BaseController::stopping | ( | ) | [virtual] |
Stops the thread.
Reimplemented from pr2_controller_interface::Controller.
Definition at line 308 of file base_controller.cpp.
void BaseController::update | ( | void | ) | [virtual] |
Updates the effort on all base joints. Also checks if the robot is standing still and takes appropriate action.
Updates the effort on all base joints, taking into account a possible new command. If the robot is detected to stand still, sets still=true. If the still=true and the desired velocity is zero, disconnects the controller.
Implements pr2_controller_interface::Controller.
Definition at line 194 of file base_controller.cpp.
void BaseController::VelCallback | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) | [private] |
Handles incoming /cmd_vel messages.
Automatically called when a new message is detected. Computes the limited command velocity and sets new_cmd_available to true.
msg | the /cmd_vel messages it parses |
Definition at line 312 of file base_controller.cpp.
Definition at line 150 of file base_controller.h.
geometry_msgs::Twist controller::BaseController::cmd_vel_ [private] |
Definition at line 139 of file base_controller.h.
double controller::BaseController::current_pos_phi [private] |
Definition at line 96 of file base_controller.h.
double controller::BaseController::current_pos_x [private] |
Definition at line 94 of file base_controller.h.
double controller::BaseController::current_pos_y [private] |
Definition at line 95 of file base_controller.h.
Definition at line 151 of file base_controller.h.
double controller::BaseController::damping_phi [private] |
Definition at line 126 of file base_controller.h.
double controller::BaseController::damping_x [private] |
Definition at line 124 of file base_controller.h.
double controller::BaseController::damping_y [private] |
Definition at line 125 of file base_controller.h.
double controller::BaseController::desired_pos_phi [private] |
Definition at line 100 of file base_controller.h.
double controller::BaseController::desired_pos_x [private] |
Definition at line 98 of file base_controller.h.
double controller::BaseController::desired_pos_y [private] |
Definition at line 99 of file base_controller.h.
double controller::BaseController::inertia_phi [private] |
Definition at line 122 of file base_controller.h.
double controller::BaseController::Kd_phi [private] |
Definition at line 116 of file base_controller.h.
double controller::BaseController::Kd_x [private] |
Definition at line 110 of file base_controller.h.
double controller::BaseController::Kd_y [private] |
Definition at line 113 of file base_controller.h.
double controller::BaseController::Kp_phi [private] |
Definition at line 115 of file base_controller.h.
double controller::BaseController::Kp_x [private] |
Definition at line 109 of file base_controller.h.
double controller::BaseController::Kp_y [private] |
Definition at line 112 of file base_controller.h.
double controller::BaseController::mass_x [private] |
Definition at line 120 of file base_controller.h.
double controller::BaseController::mass_y [private] |
Definition at line 121 of file base_controller.h.
geometry_msgs::Twist controller::BaseController::max_accel_ [private] |
Definition at line 143 of file base_controller.h.
double controller::BaseController::max_rotational_velocity_ [private] |
Definition at line 133 of file base_controller.h.
double controller::BaseController::max_translational_velocity_ [private] |
Definition at line 132 of file base_controller.h.
geometry_msgs::Twist controller::BaseController::ref_vel_last_ [private] |
Definition at line 141 of file base_controller.h.
pointer to the robot
Definition at line 146 of file base_controller.h.
double controller::BaseController::rot_vel_min [private] |
Definition at line 105 of file base_controller.h.
Definition at line 149 of file base_controller.h.
double controller::BaseController::timeout_ [private] |
maximum time between commands before controller resets the (reference) velocity
Definition at line 136 of file base_controller.h.
double controller::BaseController::trans_vel_min [private] |
Definition at line 104 of file base_controller.h.
double controller::BaseController::u_phi_max [private] |
Definition at line 130 of file base_controller.h.
double controller::BaseController::u_x_max [private] |
Definition at line 128 of file base_controller.h.
double controller::BaseController::u_y_max [private] |
Definition at line 129 of file base_controller.h.
Definition at line 84 of file base_controller.h.
Definition at line 87 of file base_controller.h.
Definition at line 88 of file base_controller.h.
pr2_mechanism_model::JointState* controller::BaseController::wheel_inner_right_front_state [private] |
Definition at line 89 of file base_controller.h.
Definition at line 90 of file base_controller.h.