$search

controller::BaseController Class Reference

#include <base_controller.h>

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

List of all members.

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::RobotStaterobot_
 pointer to the robot
double timeout_
 maximum time between commands before controller resets the (reference) velocity
ros::Subscriber vel_sub

ros::Time cmd_received_timestamp_
ros::Time current_time
ros::Time time_of_last_cycle_

geometry_msgs::Twist cmd_vel_
geometry_msgs::Twist max_accel_
geometry_msgs::Twist ref_vel_last_

double current_pos_phi
double current_pos_x
double current_pos_y
double desired_pos_phi
double desired_pos_x
double desired_pos_y

double damping_phi
double damping_x
double damping_y
double inertia_phi
double mass_x
double mass_y
double max_rotational_velocity_
double max_translational_velocity_
double u_phi_max
double u_x_max
double u_y_max

double Kd_phi
double Kd_x
double Kd_y
double Kp_phi
double Kp_x
double Kp_y

double rot_vel_min
double trans_vel_min

pr2_mechanism_model::JointStatewheel_inner_left_front_state
pr2_mechanism_model::JointStatewheel_inner_left_rear_state
pr2_mechanism_model::JointStatewheel_inner_right_front_state
pr2_mechanism_model::JointStatewheel_inner_right_rear_state

Detailed Description

Definition at line 59 of file base_controller.h.


Constructor & Destructor Documentation

controller::BaseController::BaseController (  ) 

Constructor for BaseController.

controller::BaseController::~BaseController (  ) 

Deconstructor for BaseController.


Member Function Documentation

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.

Returns:
false as soon as an error occurs, true if none occurs
Parameters:
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.

Parameters:
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.

Parameters:
msg the /cmd_vel messages it parses

Member Data Documentation

Definition at line 150 of file base_controller.h.

Definition at line 139 of file base_controller.h.

Definition at line 96 of file base_controller.h.

Definition at line 94 of file base_controller.h.

Definition at line 95 of file base_controller.h.

Definition at line 151 of file base_controller.h.

Definition at line 126 of file base_controller.h.

Definition at line 124 of file base_controller.h.

Definition at line 125 of file base_controller.h.

Definition at line 100 of file base_controller.h.

Definition at line 98 of file base_controller.h.

Definition at line 99 of file base_controller.h.

Definition at line 122 of file base_controller.h.

Definition at line 116 of file base_controller.h.

Definition at line 110 of file base_controller.h.

Definition at line 113 of file base_controller.h.

Definition at line 115 of file base_controller.h.

Definition at line 109 of file base_controller.h.

Definition at line 112 of file base_controller.h.

Definition at line 120 of file base_controller.h.

Definition at line 121 of file base_controller.h.

Definition at line 143 of file base_controller.h.

Definition at line 133 of file base_controller.h.

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.

Definition at line 105 of file base_controller.h.

Definition at line 149 of file base_controller.h.

maximum time between commands before controller resets the (reference) velocity

Definition at line 136 of file base_controller.h.

Definition at line 104 of file base_controller.h.

Definition at line 130 of file base_controller.h.

Definition at line 128 of file base_controller.h.

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.

Definition at line 89 of file base_controller.h.

Definition at line 90 of file base_controller.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


amigo_gazebo
Author(s): Rob Janssen
autogenerated on Tue Mar 5 12:30:07 2013