#include <pr2_base_controller.h>
Public Member Functions | |
geometry_msgs::Twist | getCommand () |
Returns the current position command. | |
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
Pr2BaseController () | |
Default Constructor of the Pr2BaseController class. | |
void | setCommand (const geometry_msgs::Twist &cmd_vel) |
void | setDesiredCasterSteer () |
set the desired caster steer | |
void | setJointCommands () |
set the joint commands | |
void | starting () |
void | update () |
(a) Updates commands to caster and wheels. Called every timestep in realtime | |
~Pr2BaseController () | |
Destructor of the Pr2BaseController class. | |
Public Attributes | |
BaseKinematics | base_kin_ |
class where the robot's information is computed and stored | |
pthread_mutex_t | pr2_base_controller_lock_ |
mutex lock for setting and getting commands | |
Private Member Functions | |
void | commandCallback (const geometry_msgs::TwistConstPtr &msg) |
deal with Twist commands | |
void | computeDesiredCasterSteer (const double &dT) |
computes the desired caster speeds given the desired base speed | |
void | computeDesiredWheelSpeeds () |
computes the desired wheel speeds given the desired base speed | |
void | computeJointCommands (const double &dT) |
computes the desired caster steers and wheel speeds | |
geometry_msgs::Twist | interpolateCommand (const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT) |
interpolates velocities within a given time based on maximum accelerations | |
void | publishState (const ros::Time ¤t_time) |
Publish the state. | |
void | setDesiredWheelSpeeds () |
sends the desired wheel speeds to the wheel controllers | |
void | updateJointControllers () |
tells the wheel and caster controllers to update their speeds | |
Private Attributes | |
double | alpha_stall_ |
low pass filter value used for finding stalls | |
geometry_msgs::Twist | base_vel_msg_ |
callback message, used to remember where the base is commanded to go | |
std::vector< boost::shared_ptr < JointVelocityController > > | caster_controller_ |
vector that stores the caster controllers | |
std::vector< control_toolbox::Pid > | caster_position_pid_ |
The pid controllers for caster position. | |
filters::MultiChannelTransferFunctionFilter < double > | caster_vel_filter_ |
ros::Time | cmd_received_timestamp_ |
timestamp corresponding to when the command received by the node | |
ros::Subscriber | cmd_sub_ |
ros::Subscriber | cmd_sub_deprecated_ |
geometry_msgs::Twist | cmd_vel_ |
speed command vector used internally to represent the current commanded speed | |
double | cmd_vel_rot_eps_ |
minimum rotational velocity value allowable | |
geometry_msgs::Twist | cmd_vel_t_ |
Input speed command vector represents the desired speed requested by the node. Note that this may differ from the current commanded speed due to acceleration limits imposed by the controller. | |
double | cmd_vel_trans_eps_ |
minimum tranlational velocity value allowable | |
geometry_msgs::Twist | desired_vel_ |
Input speed command vector represents the desired speed requested by the node. | |
double | eps_ |
generic epsilon value that is used as a minimum or maximum allowable input value | |
std::vector< double > | filtered_velocity_ |
double | kp_caster_steer_ |
local gain used for speed control of the caster (to achieve resultant position control) | |
ros::Time | last_publish_time_ |
Time interval between state publishing. | |
ros::Time | last_time_ |
time corresponding to when update was last called | |
geometry_msgs::Twist | max_accel_ |
acceleration limits specified externally | |
double | max_rotational_velocity_ |
maximum rotational velocity magnitude allowable | |
double | max_translational_velocity_ |
maximum translational velocity magnitude allowable | |
geometry_msgs::Twist | max_vel_ |
velocity limits specified externally | |
bool | new_cmd_available_ |
true when new command received by node | |
ros::NodeHandle | node_ |
bool | publish_state_ |
ros::NodeHandle | root_handle_ |
double | state_publish_rate_ |
double | state_publish_time_ |
Time interval between state publishing. | |
boost::scoped_ptr < realtime_tools::RealtimePublisher < pr2_mechanism_controllers::BaseControllerState > > | state_publisher_ |
publishes information about the caster and wheel controllers | |
double | timeout_ |
timeout specifying time that the controller waits before setting the current velocity command to zero | |
std::vector< boost::shared_ptr < JointVelocityController > > | wheel_controller_ |
vector that stores the wheel controllers |
Definition at line 53 of file pr2_base_controller.h.
controller::Pr2BaseController::Pr2BaseController | ( | ) |
Default Constructor of the Pr2BaseController class.
Definition at line 43 of file pr2_base_controller.cpp.
controller::Pr2BaseController::~Pr2BaseController | ( | ) |
Destructor of the Pr2BaseController class.
Definition at line 64 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::commandCallback | ( | const geometry_msgs::TwistConstPtr & | msg | ) | [private] |
deal with Twist commands
Definition at line 463 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::computeDesiredCasterSteer | ( | const double & | dT | ) | [private] |
computes the desired caster speeds given the desired base speed
Definition at line 369 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::computeDesiredWheelSpeeds | ( | ) | [private] |
computes the desired wheel speeds given the desired base speed
Definition at line 418 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::computeJointCommands | ( | const double & | dT | ) | [private] |
computes the desired caster steers and wheel speeds
Definition at line 353 of file pr2_base_controller.cpp.
geometry_msgs::Twist controller::Pr2BaseController::getCommand | ( | ) |
Returns the current position command.
Definition at line 249 of file pr2_base_controller.cpp.
bool controller::Pr2BaseController::init | ( | pr2_mechanism_model::RobotState * | robot, | |
ros::NodeHandle & | n | |||
) |
Definition at line 70 of file pr2_base_controller.cpp.
geometry_msgs::Twist controller::Pr2BaseController::interpolateCommand | ( | const geometry_msgs::Twist & | start, | |
const geometry_msgs::Twist & | end, | |||
const geometry_msgs::Twist & | max_rate, | |||
const double & | dT | |||
) | [private] |
interpolates velocities within a given time based on maximum accelerations
Definition at line 210 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::publishState | ( | const ros::Time & | current_time | ) | [private] |
Publish the state.
Definition at line 313 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::setCommand | ( | const geometry_msgs::Twist & | cmd_vel | ) |
Definition at line 177 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::setDesiredCasterSteer | ( | ) |
set the desired caster steer
Definition at line 410 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::setDesiredWheelSpeeds | ( | ) | [private] |
sends the desired wheel speeds to the wheel controllers
Definition at line 447 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::setJointCommands | ( | ) |
set the joint commands
Definition at line 362 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::starting | ( | ) |
Definition at line 260 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::update | ( | ) |
(a) Updates commands to caster and wheels. Called every timestep in realtime
Definition at line 274 of file pr2_base_controller.cpp.
void controller::Pr2BaseController::updateJointControllers | ( | ) | [private] |
tells the wheel and caster controllers to update their speeds
Definition at line 455 of file pr2_base_controller.cpp.
double controller::Pr2BaseController::alpha_stall_ [private] |
low pass filter value used for finding stalls
Definition at line 190 of file pr2_base_controller.h.
class where the robot's information is computed and stored
Definition at line 93 of file pr2_base_controller.h.
geometry_msgs::Twist controller::Pr2BaseController::base_vel_msg_ [private] |
callback message, used to remember where the base is commanded to go
Definition at line 245 of file pr2_base_controller.h.
std::vector<boost::shared_ptr<JointVelocityController> > controller::Pr2BaseController::caster_controller_ [private] |
vector that stores the caster controllers
Definition at line 200 of file pr2_base_controller.h.
std::vector<control_toolbox::Pid> controller::Pr2BaseController::caster_position_pid_ [private] |
The pid controllers for caster position.
Definition at line 283 of file pr2_base_controller.h.
filters::MultiChannelTransferFunctionFilter<double> controller::Pr2BaseController::caster_vel_filter_ [private] |
Definition at line 285 of file pr2_base_controller.h.
ros::Time controller::Pr2BaseController::cmd_received_timestamp_ [private] |
timestamp corresponding to when the command received by the node
Definition at line 144 of file pr2_base_controller.h.
ros::Subscriber controller::Pr2BaseController::cmd_sub_ [private] |
Definition at line 122 of file pr2_base_controller.h.
ros::Subscriber controller::Pr2BaseController::cmd_sub_deprecated_ [private] |
Definition at line 124 of file pr2_base_controller.h.
geometry_msgs::Twist controller::Pr2BaseController::cmd_vel_ [private] |
speed command vector used internally to represent the current commanded speed
Definition at line 155 of file pr2_base_controller.h.
double controller::Pr2BaseController::cmd_vel_rot_eps_ [private] |
minimum rotational velocity value allowable
Definition at line 255 of file pr2_base_controller.h.
geometry_msgs::Twist controller::Pr2BaseController::cmd_vel_t_ [private] |
Input speed command vector represents the desired speed requested by the node. Note that this may differ from the current commanded speed due to acceleration limits imposed by the controller.
Definition at line 150 of file pr2_base_controller.h.
double controller::Pr2BaseController::cmd_vel_trans_eps_ [private] |
minimum tranlational velocity value allowable
Definition at line 270 of file pr2_base_controller.h.
geometry_msgs::Twist controller::Pr2BaseController::desired_vel_ [private] |
Input speed command vector represents the desired speed requested by the node.
Definition at line 160 of file pr2_base_controller.h.
double controller::Pr2BaseController::eps_ [private] |
generic epsilon value that is used as a minimum or maximum allowable input value
Definition at line 250 of file pr2_base_controller.h.
std::vector<double> controller::Pr2BaseController::filtered_velocity_ [private] |
Definition at line 287 of file pr2_base_controller.h.
double controller::Pr2BaseController::kp_caster_steer_ [private] |
local gain used for speed control of the caster (to achieve resultant position control)
Definition at line 185 of file pr2_base_controller.h.
ros::Time controller::Pr2BaseController::last_publish_time_ [private] |
Time interval between state publishing.
Definition at line 265 of file pr2_base_controller.h.
ros::Time controller::Pr2BaseController::last_time_ [private] |
time corresponding to when update was last called
Definition at line 139 of file pr2_base_controller.h.
geometry_msgs::Twist controller::Pr2BaseController::max_accel_ [private] |
acceleration limits specified externally
Definition at line 170 of file pr2_base_controller.h.
double controller::Pr2BaseController::max_rotational_velocity_ [private] |
maximum rotational velocity magnitude allowable
Definition at line 180 of file pr2_base_controller.h.
double controller::Pr2BaseController::max_translational_velocity_ [private] |
maximum translational velocity magnitude allowable
Definition at line 175 of file pr2_base_controller.h.
geometry_msgs::Twist controller::Pr2BaseController::max_vel_ [private] |
velocity limits specified externally
Definition at line 165 of file pr2_base_controller.h.
bool controller::Pr2BaseController::new_cmd_available_ [private] |
true when new command received by node
Definition at line 134 of file pr2_base_controller.h.
ros::NodeHandle controller::Pr2BaseController::node_ [private] |
Definition at line 118 of file pr2_base_controller.h.
pthread_mutex_t controller::Pr2BaseController::pr2_base_controller_lock_ |
mutex lock for setting and getting commands
Definition at line 98 of file pr2_base_controller.h.
bool controller::Pr2BaseController::publish_state_ [private] |
Definition at line 278 of file pr2_base_controller.h.
ros::NodeHandle controller::Pr2BaseController::root_handle_ [private] |
Definition at line 120 of file pr2_base_controller.h.
double controller::Pr2BaseController::state_publish_rate_ [private] |
Definition at line 260 of file pr2_base_controller.h.
double controller::Pr2BaseController::state_publish_time_ [private] |
Time interval between state publishing.
Definition at line 260 of file pr2_base_controller.h.
boost::scoped_ptr<realtime_tools::RealtimePublisher<pr2_mechanism_controllers::BaseControllerState> > controller::Pr2BaseController::state_publisher_ [private] |
publishes information about the caster and wheel controllers
Definition at line 205 of file pr2_base_controller.h.
double controller::Pr2BaseController::timeout_ [private] |
timeout specifying time that the controller waits before setting the current velocity command to zero
Definition at line 129 of file pr2_base_controller.h.
std::vector<boost::shared_ptr<JointVelocityController> > controller::Pr2BaseController::wheel_controller_ [private] |
vector that stores the wheel controllers
Definition at line 195 of file pr2_base_controller.h.