Go to the documentation of this file.
37 #include <nav_msgs/Odometry.h>
38 #include <pr2_mechanism_controllers/Odometer.h>
40 #include <tf/tfMessage.h>
45 #include <boost/scoped_ptr.hpp>
47 #include <std_msgs/Float64.h>
48 #include <pr2_mechanism_controllers/OdometryMatrix.h>
49 #include <pr2_mechanism_controllers/DebugInfo.h>
51 #include <std_msgs/Bool.h>
52 #include <pr2_mechanism_controllers/BaseOdometryState.h>
122 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
153 void getOdometry(
double &x,
double &y,
double &yaw,
double &vx,
double &vy,
double &vw);
160 void getOdometry(geometry_msgs::Point &odom, geometry_msgs::Twist &odom_vel);
201 geometry_msgs::Point
odom_;
271 boost::scoped_ptr<realtime_tools::RealtimePublisher <nav_msgs::Odometry> >
odometry_publisher_ ;
276 boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::Odometer> >
odometer_publisher_ ;
281 boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::BaseOdometryState> >
state_publisher_ ;
301 boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::OdometryMatrix> >
matrix_publisher_;
302 boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::DebugInfo> >
debug_publisher_;
void publishTransform()
Publishes the currently computed odometry information to tf.
boost::scoped_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > transform_publisher_
Publishes the transform between the odometry frame and the base frame.
Eigen::Matrix< float, 16, 16 > OdomMatrix16x16
Pr2Odometry()
Constructor for the odometry.
Eigen::Matrix< float, 3, 1 > OdomMatrix3x1
double odometry_residual_max_
Maximum residual from the iteritive least squares.
double caster_calibration_multiplier_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::Odometer > > odometer_publisher_
The RealtimePublisher that does the realtime publishing of the odometry.
ros::Time last_time_
Stores the last update time and the current update time.
BaseKinematics base_kin_
class where the robot's information is computed and stored
int ils_max_iterations_
Number of iterations used during iterative least squares.
double getCorrectedWheelSpeed(const int &index)
Computes the wheel's speed adjusted for the attached caster's rotational velocity.
double odometer_publish_rate_
~Pr2Odometry()
Destructor for the odometry.
void update()
(a) Updates positions of the caster and wheels. Called every timestep in realtime
ros::Time last_state_publish_time_
The last time the odometry information was published.
ros::Time last_transform_publish_time_
The last time the odometry information was published.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseOdometryState > > state_publisher_
The RealtimePublisher that does the realtime publishing of the odometry state.
Eigen::Matrix< float, 16, 3 > OdomMatrix16x3
geometry_msgs::Point odom_
Point that stores the current translational position (x,y) and angular position (z)
ros::Time last_odometer_publish_time_
The last time the odometry information was published.
bool publish_tf_
enable or disable tf publishing
OdomMatrix16x1 fit_residual_
double odometer_distance_
Total distance traveled by the base as computed by the odometer.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::DebugInfo > > debug_publisher_
double odom_publish_rate_
geometry_msgs::Twist odom_vel_
Twist that remembers the current translational velocities (vel.vx, vel.vy) and angular position (ang_...
double state_publish_rate_
OdomMatrix16x16 findWeightMatrix(const OdomMatrix16x1 &residual)
Finds the weight matrix from the iterative least squares residuals.
void publishOdometer()
Publishes the currently computed odometer information.
std::string base_footprint_frame_
The topic name of the base footprint frame.
double expected_odometer_publish_time_
The time that the odometry is expected to be published next.
boost::scoped_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odometry_publisher_
The RealtimePublisher that does the realtime publishing of the odometry.
void populateCovariance(const double &residual, nav_msgs::Odometry &msg)
populate the covariance part of the odometry message
OdomMatrix16x1 odometry_residual_
double expected_state_publish_time_
The time that the odometry is expected to be published next.
Eigen::Matrix< float, 16, 1 > OdomMatrix16x1
void computeBaseVelocity()
Computes the base velocity from the caster positions and wheel speeds.
double base_link_floor_z_offset_
ros::Time last_publish_time_
The last time the odometry information was published.
OdomMatrix16x16 weight_matrix_
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
Initializes and loads odometry information from the param server.
double expected_publish_time_
The time that the odometry is expected to be published next.
void getOdometry(double &x, double &y, double &yaw, double &vx, double &vy, double &vw)
Takes the current odometery information and stores it into the six double parameters.
void publish()
Publishes the currently computed odometry information.
std::string base_link_frame_
The topic name of the base link frame.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::OdometryMatrix > > matrix_publisher_
double odometer_angle_
Total angular distance traveled by the base as computed by the odometer.
void getOdometryMessage(nav_msgs::Odometry &msg)
Builds the odometry message and prepares it for sending.
void publishState()
Publishes the odometry state information.
OdomMatrix3x1 iterativeLeastSquares(const OdomMatrix16x3 &lhs, const OdomMatrix16x1 &rhs, const int &max_iter)
Function used to compute the most likely solution to the odometry using iterative least squares.
void updateOdometry()
Finds and stores the latest odometry information.
std::string odom_frame_
The topic name of the published odometry.