$search
#include <base_controller.h>
Definition at line 59 of file base_controller.h.
controller::BaseController::BaseController | ( | ) |
Constructor for BaseController.
controller::BaseController::~BaseController | ( | ) |
Deconstructor for BaseController.
virtual bool controller::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.
geometry_msgs::Twist controller::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 |
virtual void controller::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.
virtual void controller::BaseController::stopping | ( | ) | [virtual] |
Stops the thread.
Reimplemented from pr2_controller_interface::Controller.
virtual void controller::BaseController::update | ( | ) | [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.
void controller::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 150 of file base_controller.h.
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.
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.
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.