Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
controller::Pr2BaseController2 Class Reference

#include <pr2_base_controller2.h>

Inheritance diagram for controller::Pr2BaseController2:
Inheritance graph
[legend]

Public Member Functions

geometry_msgs::Twist getCommand ()
 Returns the current position command. More...
 
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
 Pr2BaseController2 ()
 Default Constructor of the Pr2BaseController2 class. More...
 
void setCommand (const geometry_msgs::Twist &cmd_vel)
 
void setDesiredCasterSteer ()
 set the desired caster steer More...
 
void setJointCommands ()
 set the joint commands More...
 
void starting ()
 
void update ()
 (a) Updates commands to caster and wheels. Called every timestep in realtime More...
 
 ~Pr2BaseController2 ()
 Destructor of the Pr2BaseController2 class. More...
 
- Public Member Functions inherited from pr2_controller_interface::Controller
 Controller ()
 
bool getController (const std::string &name, int sched, ControllerType *&c)
 
bool initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
bool isRunning ()
 
void starting (const ros::Time &time)
 
bool startRequest ()
 
virtual void stopping ()
 
void stopping (const ros::Time &time)
 
bool stopRequest ()
 
void update (const ros::Time &time, const ros::Duration &period)
 
void updateRequest ()
 
virtual ~Controller ()
 

Public Attributes

BaseKinematics base_kinematics_
 class where the robot's information is computed and stored More...
 
pthread_mutex_t pr2_base_controller_lock_
 mutex lock for setting and getting commands More...
 
- Public Attributes inherited from pr2_controller_interface::Controller
std::vector< std::string > after_list_
 
 AFTER_ME
 
std::vector< std::string > before_list_
 
 BEFORE_ME
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum pr2_controller_interface::Controller:: { ... }  state_
 

Private Member Functions

void commandCallback (const geometry_msgs::TwistConstPtr &msg)
 deal with Twist commands More...
 
void computeDesiredCasterSteer (const double &dT)
 computes the desired caster speeds given the desired base speed More...
 
void computeDesiredWheelSpeeds (const double &dT)
 computes the desired wheel speeds given the desired base speed More...
 
void computeJointCommands (const double &dT)
 computes the desired caster steers and wheel speeds More...
 
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 More...
 
void publishState (const ros::Time &current_time)
 Publish the state. More...
 
void setDesiredWheelSpeeds ()
 sends the desired wheel speeds to the wheel controllers More...
 
void updateJointControllers ()
 tells the wheel and caster controllers to update their speeds More...
 

Private Attributes

double alpha_stall_
 low pass filter value used for finding stalls More...
 
geometry_msgs::Twist base_vel_msg_
 callback message, used to remember where the base is commanded to go More...
 
std::vector< boost::shared_ptr< JointVelocityController > > caster_controller_
 vector that stores the caster controllers More...
 
std::vector< control_toolbox::Pidcaster_position_pid_
 The pid controllers for caster position. More...
 
filters::MultiChannelTransferFunctionFilter< double > caster_vel_filter_
 
ros::Time cmd_received_timestamp_
 timestamp corresponding to when the command received by the node More...
 
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 More...
 
double cmd_vel_rot_eps_
 minimum rotational velocity value allowable More...
 
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. More...
 
double cmd_vel_trans_eps_
 minimum tranlational velocity value allowable More...
 
geometry_msgs::Twist desired_vel_
 Input speed command vector represents the desired speed requested by the node. More...
 
double eps_
 generic epsilon value that is used as a minimum or maximum allowable input value More...
 
std::vector< double > filtered_velocity_
 
std::vector< double > filtered_wheel_velocity_
 
double kp_caster_steer_
 local gain used for speed control of the caster (to achieve resultant position control) More...
 
ros::Time last_publish_time_
 Time interval between state publishing. More...
 
ros::Time last_time_
 time corresponding to when update was last called More...
 
geometry_msgs::Twist max_accel_
 acceleration limits specified externally More...
 
double max_rotational_velocity_
 maximum rotational velocity magnitude allowable More...
 
double max_translational_velocity_
 maximum translational velocity magnitude allowable More...
 
geometry_msgs::Twist max_vel_
 velocity limits specified externally More...
 
bool new_cmd_available_
 true when new command received by node More...
 
ros::NodeHandle node_
 
bool publish_state_
 
ros::NodeHandle root_handle_
 
double state_publish_rate_
 
double state_publish_time_
 Time interval between state publishing. More...
 
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseControllerState2 > > state_publisher_
 publishes information about the caster and wheel controllers More...
 
double timeout_
 timeout specifying time that the controller waits before setting the current velocity command to zero More...
 
std::vector< boost::shared_ptr< JointVelocityController > > wheel_controller_
 vector that stores the wheel controllers More...
 
std::vector< control_toolbox::Pidwheel_pid_controllers_
 The pid controllers for caster position. More...
 
filters::MultiChannelTransferFunctionFilter< double > wheel_vel_filter_
 

Detailed Description

Definition at line 86 of file pr2_base_controller2.h.

Constructor & Destructor Documentation

◆ Pr2BaseController2()

controller::Pr2BaseController2::Pr2BaseController2 ( )

Default Constructor of the Pr2BaseController2 class.

Definition at line 79 of file pr2_base_controller2.cpp.

◆ ~Pr2BaseController2()

controller::Pr2BaseController2::~Pr2BaseController2 ( )

Destructor of the Pr2BaseController2 class.

Definition at line 100 of file pr2_base_controller2.cpp.

Member Function Documentation

◆ commandCallback()

void controller::Pr2BaseController2::commandCallback ( const geometry_msgs::TwistConstPtr &  msg)
private

deal with Twist commands

Definition at line 526 of file pr2_base_controller2.cpp.

◆ computeDesiredCasterSteer()

void controller::Pr2BaseController2::computeDesiredCasterSteer ( const double &  dT)
private

computes the desired caster speeds given the desired base speed

Definition at line 413 of file pr2_base_controller2.cpp.

◆ computeDesiredWheelSpeeds()

void controller::Pr2BaseController2::computeDesiredWheelSpeeds ( const double &  dT)
private

computes the desired wheel speeds given the desired base speed

Definition at line 469 of file pr2_base_controller2.cpp.

◆ computeJointCommands()

void controller::Pr2BaseController2::computeJointCommands ( const double &  dT)
private

computes the desired caster steers and wheel speeds

Definition at line 397 of file pr2_base_controller2.cpp.

◆ getCommand()

geometry_msgs::Twist controller::Pr2BaseController2::getCommand ( )

Returns the current position command.

Returns
Current velocity command

Definition at line 292 of file pr2_base_controller2.cpp.

◆ init()

bool controller::Pr2BaseController2::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
)
virtual

Implements pr2_controller_interface::Controller.

Definition at line 106 of file pr2_base_controller2.cpp.

◆ interpolateCommand()

geometry_msgs::Twist controller::Pr2BaseController2::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 253 of file pr2_base_controller2.cpp.

◆ publishState()

void controller::Pr2BaseController2::publishState ( const ros::Time current_time)
private

Publish the state.

Definition at line 356 of file pr2_base_controller2.cpp.

◆ setCommand()

void controller::Pr2BaseController2::setCommand ( const geometry_msgs::Twist &  cmd_vel)

Definition at line 220 of file pr2_base_controller2.cpp.

◆ setDesiredCasterSteer()

void controller::Pr2BaseController2::setDesiredCasterSteer ( )

set the desired caster steer

Definition at line 461 of file pr2_base_controller2.cpp.

◆ setDesiredWheelSpeeds()

void controller::Pr2BaseController2::setDesiredWheelSpeeds ( )
private

sends the desired wheel speeds to the wheel controllers

Definition at line 510 of file pr2_base_controller2.cpp.

◆ setJointCommands()

void controller::Pr2BaseController2::setJointCommands ( )

set the joint commands

Definition at line 406 of file pr2_base_controller2.cpp.

◆ starting()

void controller::Pr2BaseController2::starting ( )
virtual

Reimplemented from pr2_controller_interface::Controller.

Definition at line 303 of file pr2_base_controller2.cpp.

◆ update()

void controller::Pr2BaseController2::update ( )
virtual

(a) Updates commands to caster and wheels. Called every timestep in realtime

Implements pr2_controller_interface::Controller.

Definition at line 317 of file pr2_base_controller2.cpp.

◆ updateJointControllers()

void controller::Pr2BaseController2::updateJointControllers ( )
private

tells the wheel and caster controllers to update their speeds

Definition at line 518 of file pr2_base_controller2.cpp.

Member Data Documentation

◆ alpha_stall_

double controller::Pr2BaseController2::alpha_stall_
private

low pass filter value used for finding stalls

Definition at line 223 of file pr2_base_controller2.h.

◆ base_kinematics_

BaseKinematics controller::Pr2BaseController2::base_kinematics_

class where the robot's information is computed and stored

Returns
BaseKinematic instance that is being used by this controller

Definition at line 126 of file pr2_base_controller2.h.

◆ base_vel_msg_

geometry_msgs::Twist controller::Pr2BaseController2::base_vel_msg_
private

callback message, used to remember where the base is commanded to go

Definition at line 278 of file pr2_base_controller2.h.

◆ caster_controller_

std::vector<boost::shared_ptr<JointVelocityController> > controller::Pr2BaseController2::caster_controller_
private

vector that stores the caster controllers

Definition at line 233 of file pr2_base_controller2.h.

◆ caster_position_pid_

std::vector<control_toolbox::Pid> controller::Pr2BaseController2::caster_position_pid_
private

The pid controllers for caster position.

Definition at line 316 of file pr2_base_controller2.h.

◆ caster_vel_filter_

filters::MultiChannelTransferFunctionFilter<double> controller::Pr2BaseController2::caster_vel_filter_
private

Definition at line 318 of file pr2_base_controller2.h.

◆ cmd_received_timestamp_

ros::Time controller::Pr2BaseController2::cmd_received_timestamp_
private

timestamp corresponding to when the command received by the node

Definition at line 177 of file pr2_base_controller2.h.

◆ cmd_sub_

ros::Subscriber controller::Pr2BaseController2::cmd_sub_
private

Definition at line 155 of file pr2_base_controller2.h.

◆ cmd_sub_deprecated_

ros::Subscriber controller::Pr2BaseController2::cmd_sub_deprecated_
private

Definition at line 157 of file pr2_base_controller2.h.

◆ cmd_vel_

geometry_msgs::Twist controller::Pr2BaseController2::cmd_vel_
private

speed command vector used internally to represent the current commanded speed

Definition at line 188 of file pr2_base_controller2.h.

◆ cmd_vel_rot_eps_

double controller::Pr2BaseController2::cmd_vel_rot_eps_
private

minimum rotational velocity value allowable

Definition at line 288 of file pr2_base_controller2.h.

◆ cmd_vel_t_

geometry_msgs::Twist controller::Pr2BaseController2::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 183 of file pr2_base_controller2.h.

◆ cmd_vel_trans_eps_

double controller::Pr2BaseController2::cmd_vel_trans_eps_
private

minimum tranlational velocity value allowable

Definition at line 303 of file pr2_base_controller2.h.

◆ desired_vel_

geometry_msgs::Twist controller::Pr2BaseController2::desired_vel_
private

Input speed command vector represents the desired speed requested by the node.

Definition at line 193 of file pr2_base_controller2.h.

◆ eps_

double controller::Pr2BaseController2::eps_
private

generic epsilon value that is used as a minimum or maximum allowable input value

Definition at line 283 of file pr2_base_controller2.h.

◆ filtered_velocity_

std::vector<double> controller::Pr2BaseController2::filtered_velocity_
private

Definition at line 320 of file pr2_base_controller2.h.

◆ filtered_wheel_velocity_

std::vector<double> controller::Pr2BaseController2::filtered_wheel_velocity_
private

Definition at line 324 of file pr2_base_controller2.h.

◆ kp_caster_steer_

double controller::Pr2BaseController2::kp_caster_steer_
private

local gain used for speed control of the caster (to achieve resultant position control)

Definition at line 218 of file pr2_base_controller2.h.

◆ last_publish_time_

ros::Time controller::Pr2BaseController2::last_publish_time_
private

Time interval between state publishing.

Definition at line 298 of file pr2_base_controller2.h.

◆ last_time_

ros::Time controller::Pr2BaseController2::last_time_
private

time corresponding to when update was last called

Definition at line 172 of file pr2_base_controller2.h.

◆ max_accel_

geometry_msgs::Twist controller::Pr2BaseController2::max_accel_
private

acceleration limits specified externally

Definition at line 203 of file pr2_base_controller2.h.

◆ max_rotational_velocity_

double controller::Pr2BaseController2::max_rotational_velocity_
private

maximum rotational velocity magnitude allowable

Definition at line 213 of file pr2_base_controller2.h.

◆ max_translational_velocity_

double controller::Pr2BaseController2::max_translational_velocity_
private

maximum translational velocity magnitude allowable

Definition at line 208 of file pr2_base_controller2.h.

◆ max_vel_

geometry_msgs::Twist controller::Pr2BaseController2::max_vel_
private

velocity limits specified externally

Definition at line 198 of file pr2_base_controller2.h.

◆ new_cmd_available_

bool controller::Pr2BaseController2::new_cmd_available_
private

true when new command received by node

Definition at line 167 of file pr2_base_controller2.h.

◆ node_

ros::NodeHandle controller::Pr2BaseController2::node_
private

Definition at line 151 of file pr2_base_controller2.h.

◆ pr2_base_controller_lock_

pthread_mutex_t controller::Pr2BaseController2::pr2_base_controller_lock_

mutex lock for setting and getting commands

Definition at line 131 of file pr2_base_controller2.h.

◆ publish_state_

bool controller::Pr2BaseController2::publish_state_
private

Definition at line 311 of file pr2_base_controller2.h.

◆ root_handle_

ros::NodeHandle controller::Pr2BaseController2::root_handle_
private

Definition at line 153 of file pr2_base_controller2.h.

◆ state_publish_rate_

double controller::Pr2BaseController2::state_publish_rate_
private

Definition at line 293 of file pr2_base_controller2.h.

◆ state_publish_time_

double controller::Pr2BaseController2::state_publish_time_
private

Time interval between state publishing.

Definition at line 293 of file pr2_base_controller2.h.

◆ state_publisher_

boost::scoped_ptr<realtime_tools::RealtimePublisher<pr2_mechanism_controllers::BaseControllerState2> > controller::Pr2BaseController2::state_publisher_
private

publishes information about the caster and wheel controllers

Definition at line 238 of file pr2_base_controller2.h.

◆ timeout_

double controller::Pr2BaseController2::timeout_
private

timeout specifying time that the controller waits before setting the current velocity command to zero

Definition at line 162 of file pr2_base_controller2.h.

◆ wheel_controller_

std::vector<boost::shared_ptr<JointVelocityController> > controller::Pr2BaseController2::wheel_controller_
private

vector that stores the wheel controllers

Definition at line 228 of file pr2_base_controller2.h.

◆ wheel_pid_controllers_

std::vector<control_toolbox::Pid> controller::Pr2BaseController2::wheel_pid_controllers_
private

The pid controllers for caster position.

Definition at line 329 of file pr2_base_controller2.h.

◆ wheel_vel_filter_

filters::MultiChannelTransferFunctionFilter<double> controller::Pr2BaseController2::wheel_vel_filter_
private

Definition at line 322 of file pr2_base_controller2.h.


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


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Sat Nov 12 2022 03:33:25