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

#include <base_kinematics.h>

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. More...
 
void updatePosition ()
 Computes 2d postion of the wheel relative to the center of the base. More...
 

Public Attributes

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

Detailed Description

Definition at line 56 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_stateThe robot's current state
configTiny 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 207 of file base_kinematics.cpp.

Member Data Documentation

int controller::Wheel::direction_multiplier_

specifies the default direction of the wheel

Definition at line 114 of file base_kinematics.h.

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

JointState for this wheel joint.

Definition at line 63 of file base_kinematics.h.

std::string controller::Wheel::joint_name_

name of the joint

Definition at line 73 of file base_kinematics.h.

std::string controller::Wheel::link_name_

name of the link

Definition at line 78 of file base_kinematics.h.

geometry_msgs::Point controller::Wheel::offset_

default offset from the parent caster before any transformations

Definition at line 68 of file base_kinematics.h.

Caster* controller::Wheel::parent_

the caster on which this wheel is mounted

Definition at line 89 of file base_kinematics.h.

geometry_msgs::Point controller::Wheel::position_

offset_ after rotation transformation from the parent caster's position

Definition at line 84 of file base_kinematics.h.

double controller::Wheel::wheel_radius_

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

Definition at line 124 of file base_kinematics.h.

double controller::Wheel::wheel_speed_actual_

actual wheel speeds

Definition at line 94 of file base_kinematics.h.

double controller::Wheel::wheel_speed_cmd_

desired wheel speed

Definition at line 99 of file base_kinematics.h.

double controller::Wheel::wheel_speed_error_

difference between desired and actual speed

Definition at line 104 of file base_kinematics.h.

double controller::Wheel::wheel_speed_filtered_

wheel speed filtered with alpha

Definition at line 109 of file base_kinematics.h.

int controller::Wheel::wheel_stuck_

remembers if the wheel is stalled

Definition at line 119 of file base_kinematics.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 Wed Jun 5 2019 19:34:08