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

#include <base_kinematics.h>

Public Member Functions

void computeWheelPositions ()
 Computes 2d postion of every wheel relative to the center of the base. More...
 
bool init (pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
 Loads BaseKinematic's information from the xml description file and param server. More...
 
geometry_msgs::Twist pointVel2D (const geometry_msgs::Point &pos, const geometry_msgs::Twist &vel)
 Computes 2d velocity of a point at relative distance pos to another point with velocity (and rotation (z)) vel. More...
 

Public Attributes

std::vector< Castercaster_
 vector of every caster attached to the base More...
 
double MAX_DT_
 maximum dT used in computation of interpolated velocity command More...
 
std::string name_
 name of this BaseKinematics (generally associated with whatever controller is using it) More...
 
int num_casters_
 number of casters connected to the base More...
 
int num_wheels_
 number of wheels connected to the base More...
 
std::string robot_base_id_
 Name(string id) of the robot base frame. More...
 
pr2_mechanism_model::RobotStaterobot_state_
 remembers everything about the state of the robot More...
 
std::vector< Wheelwheel_
 vector of every wheel attached to the base More...
 
std::string xml_caster_name_
 the name of the casters in the xml file More...
 
std::string xml_wheel_name_
 the name of the wheels in the xml file More...
 

Detailed Description

Definition at line 229 of file base_kinematics.h.

Member Function Documentation

void BaseKinematics::computeWheelPositions ( )

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

Definition at line 218 of file base_kinematics.cpp.

bool BaseKinematics::init ( pr2_mechanism_model::RobotState robot_state,
ros::NodeHandle node 
)

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

Parameters
robot_stateThe robot's current state
configTiny xml element pointing to its controller
Returns
Successful init

Definition at line 156 of file base_kinematics.cpp.

geometry_msgs::Twist BaseKinematics::pointVel2D ( const geometry_msgs::Point pos,
const geometry_msgs::Twist &  vel 
)

Computes 2d velocity of a point at relative distance pos to another point with velocity (and rotation (z)) vel.

Parameters
posThe position of the object relative to the center of rotation
velVelocity of the center of rotation
Returns
Velocity at the given point

Definition at line 227 of file base_kinematics.cpp.

Member Data Documentation

std::vector<Caster> controller::BaseKinematics::caster_

vector of every caster attached to the base

Definition at line 277 of file base_kinematics.h.

double controller::BaseKinematics::MAX_DT_

maximum dT used in computation of interpolated velocity command

Definition at line 297 of file base_kinematics.h.

std::string controller::BaseKinematics::name_

name of this BaseKinematics (generally associated with whatever controller is using it)

Definition at line 292 of file base_kinematics.h.

int controller::BaseKinematics::num_casters_

number of casters connected to the base

Definition at line 267 of file base_kinematics.h.

int controller::BaseKinematics::num_wheels_

number of wheels connected to the base

Definition at line 262 of file base_kinematics.h.

std::string controller::BaseKinematics::robot_base_id_

Name(string id) of the robot base frame.

Definition at line 302 of file base_kinematics.h.

pr2_mechanism_model::RobotState* controller::BaseKinematics::robot_state_

remembers everything about the state of the robot

Definition at line 257 of file base_kinematics.h.

std::vector<Wheel> controller::BaseKinematics::wheel_

vector of every wheel attached to the base

Definition at line 272 of file base_kinematics.h.

std::string controller::BaseKinematics::xml_caster_name_

the name of the casters in the xml file

Definition at line 282 of file base_kinematics.h.

std::string controller::BaseKinematics::xml_wheel_name_

the name of the wheels in the xml file

Definition at line 287 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