$search

controller::BaseOdometry Class Reference

#include <pub_odometry.h>

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

List of all members.

Public Member Functions

bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 Initializes all parameters needed for start publishing.
void starting ()
 Start the thread and sets last publish times to now.
void stopping ()
 Stops the thread.
void update ()
 Updates the odometry and then checks if enough time has passed to publish something by calling the private publishing methods. Called periodically.

Private Member Functions

void computeBaseVelocity ()
 Computes the linear x and y velocities and the angular (phi) velocity. Called by updateOdometry().
void getOdometryMessage (nav_msgs::Odometry &msg)
 Sets the proper values in the message given as parameter. Calls populateCovariance(). Called by publish().
void populateCovariance (nav_msgs::Odometry &msg)
 Sets the needed values in the covariance matrix of the message given as parameter. Called by getOdometryMessage().
void publish ()
 Calls getOdometryMessage to 'create' an odometry message and publishes it. Calls getOdometryMessage(). Called by update().
void publishTransform ()
 Publishes a new transformation message. Called by update().
void updateOdometry ()
 Updates position (x,y,z,distance,angle) and updates the velocities by calling computeBaseVelocity(). Called by update().

Private Attributes

std::string base_footprint_frame_
std::string base_link_frame_
ros::NodeHandle n
geometry_msgs::Point odometry_
std::string odometry_frame_
double odometry_publish_rate_
geometry_msgs::Twist odometry_vel_
pr2_mechanism_model::RobotStaterobot_
 pointer to robot
std::string tf_prefix_

double cov_x_theta_
double cov_x_y_
double cov_y_theta_
double sigma_theta_
double sigma_x_
double sigma_y_

ros::Time current_time_
double expected_publish_time_
ros::Time last_odometry_publish_time_
ros::Time last_time_
ros::Time last_transform_publish_time_
double update_time

double current_vel_phi
double current_vel_x
double current_vel_y

double current_vel_wheel_inner_left_front
double current_vel_wheel_inner_left_rear
double current_vel_wheel_inner_right_front
double current_vel_wheel_inner_right_rear
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

boost::scoped_ptr
< realtime_tools::RealtimePublisher
< nav_msgs::Odometry > > 
odometry_publisher_
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< tf::tfMessage > > 
transform_publisher_

bool publish_odometry_
bool publish_tf_

Detailed Description

Definition at line 65 of file pub_odometry.h.


Member Function Documentation

void controller::BaseOdometry::computeBaseVelocity (  )  [private]

Computes the linear x and y velocities and the angular (phi) velocity. Called by updateOdometry().

void controller::BaseOdometry::getOdometryMessage ( nav_msgs::Odometry msg  )  [private]

Sets the proper values in the message given as parameter. Calls populateCovariance(). Called by publish().

bool controller::BaseOdometry::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
) [virtual]

Initializes all parameters needed for start publishing.

Implements pr2_controller_interface::Controller.

void controller::BaseOdometry::populateCovariance ( nav_msgs::Odometry msg  )  [private]

Sets the needed values in the covariance matrix of the message given as parameter. Called by getOdometryMessage().

void controller::BaseOdometry::publish (  )  [private]

Calls getOdometryMessage to 'create' an odometry message and publishes it. Calls getOdometryMessage(). Called by update().

void controller::BaseOdometry::publishTransform (  )  [private]

Publishes a new transformation message. Called by update().

void controller::BaseOdometry::starting (  )  [virtual]

Start the thread and sets last publish times to now.

Reimplemented from pr2_controller_interface::Controller.

void controller::BaseOdometry::stopping (  )  [virtual]

Stops the thread.

Reimplemented from pr2_controller_interface::Controller.

void controller::BaseOdometry::update (  )  [virtual]

Updates the odometry and then checks if enough time has passed to publish something by calling the private publishing methods. Called periodically.

Implements pr2_controller_interface::Controller.

void controller::BaseOdometry::updateOdometry (  )  [private]

Updates position (x,y,z,distance,angle) and updates the velocities by calling computeBaseVelocity(). Called by update().


Member Data Documentation

Definition at line 123 of file pub_odometry.h.

Definition at line 122 of file pub_odometry.h.

Definition at line 128 of file pub_odometry.h.

Definition at line 128 of file pub_odometry.h.

Definition at line 128 of file pub_odometry.h.

Definition at line 133 of file pub_odometry.h.

Definition at line 150 of file pub_odometry.h.

Definition at line 146 of file pub_odometry.h.

Definition at line 146 of file pub_odometry.h.

Definition at line 146 of file pub_odometry.h.

Definition at line 146 of file pub_odometry.h.

Definition at line 150 of file pub_odometry.h.

Definition at line 150 of file pub_odometry.h.

Definition at line 137 of file pub_odometry.h.

Definition at line 135 of file pub_odometry.h.

Definition at line 132 of file pub_odometry.h.

Definition at line 135 of file pub_odometry.h.

Definition at line 103 of file pub_odometry.h.

Definition at line 118 of file pub_odometry.h.

Definition at line 121 of file pub_odometry.h.

Definition at line 113 of file pub_odometry.h.

Definition at line 108 of file pub_odometry.h.

Definition at line 119 of file pub_odometry.h.

Definition at line 115 of file pub_odometry.h.

Definition at line 115 of file pub_odometry.h.

pointer to robot

Definition at line 105 of file pub_odometry.h.

Definition at line 128 of file pub_odometry.h.

Covariance variables

Definition at line 128 of file pub_odometry.h.

Definition at line 128 of file pub_odometry.h.

std::string controller::BaseOdometry::tf_prefix_ [private]

Definition at line 124 of file pub_odometry.h.

Definition at line 110 of file pub_odometry.h.

Definition at line 138 of file pub_odometry.h.

Definition at line 142 of file pub_odometry.h.

Definition at line 143 of file pub_odometry.h.

Definition at line 144 of file pub_odometry.h.

Definition at line 145 of file pub_odometry.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