controller::Wheel Class Reference

#include <base_kinematics.h>

List of all members.

Public Member Functions

bool init (pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name)
 Loads wheel's information from the xml description file and param server.
void updatePosition ()
 Computes 2d postion of the wheel relative to the center of the base.

Public Attributes

int direction_multiplier_
 specifies the default direction of the wheel
pr2_mechanism_model::JointState * joint_
 JointState for this wheel joint.
std::string joint_name_
 name of the joint
std::string link_name_
 name of the link
geometry_msgs::Point offset_
 default offset from the parent caster before any transformations
Casterparent_
 the caster on which this wheel is mounted
geometry_msgs::Point position_
 offset_ after rotation transformation from the parent caster's position
double wheel_radius_
 wheel radius scale (based on the default wheel radius in Basekinematics)
double wheel_speed_actual_
 actual wheel speeds
double wheel_speed_cmd_
 desired wheel speed
double wheel_speed_error_
 difference between desired and actual speed
double wheel_speed_filtered_
 wheel speed filtered with alpha
int wheel_stuck_
 remembers if the wheel is stalled

Detailed Description

Definition at line 53 of file base_kinematics.h.


Member Function Documentation

bool Wheel::init ( pr2_mechanism_model::RobotState *  robot_state,
ros::NodeHandle &  node,
std::string  link_name 
)

Loads wheel's information from the xml description file and param server.

Parameters:
robot_state The robot's current state
config Tiny xml element pointing to this wheel

Definition at line 44 of file base_kinematics.cpp.

void Wheel::updatePosition (  ) 

Computes 2d postion of the wheel relative to the center of the base.

Definition at line 195 of file base_kinematics.cpp.


Member Data Documentation

specifies the default direction of the wheel

Definition at line 111 of file base_kinematics.h.

pr2_mechanism_model::JointState* controller::Wheel::joint_

JointState for this wheel joint.

Definition at line 60 of file base_kinematics.h.

name of the joint

Definition at line 70 of file base_kinematics.h.

name of the link

Definition at line 75 of file base_kinematics.h.

geometry_msgs::Point controller::Wheel::offset_

default offset from the parent caster before any transformations

Definition at line 65 of file base_kinematics.h.

the caster on which this wheel is mounted

Definition at line 86 of file base_kinematics.h.

geometry_msgs::Point controller::Wheel::position_

offset_ after rotation transformation from the parent caster's position

Definition at line 81 of file base_kinematics.h.

wheel radius scale (based on the default wheel radius in Basekinematics)

Definition at line 121 of file base_kinematics.h.

actual wheel speeds

Definition at line 91 of file base_kinematics.h.

desired wheel speed

Definition at line 96 of file base_kinematics.h.

difference between desired and actual speed

Definition at line 101 of file base_kinematics.h.

wheel speed filtered with alpha

Definition at line 106 of file base_kinematics.h.

remembers if the wheel is stalled

Definition at line 116 of file base_kinematics.h.


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


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Fri Jan 11 09:39:08 2013