37 #include <nav_msgs/Odometry.h> 38 #include <pr2_mechanism_controllers/Odometer.h> 40 #include <tf/tfMessage.h> 45 #include <boost/scoped_ptr.hpp> 46 #include <boost/thread/condition.hpp> 48 #include <std_msgs/Float64.h> 49 #include <pr2_mechanism_controllers/OdometryMatrix.h> 50 #include <pr2_mechanism_controllers/DebugInfo.h> 52 #include <std_msgs/Bool.h> 53 #include <pr2_mechanism_controllers/BaseOdometryState.h> 123 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
154 void getOdometry(
double &x,
double &y,
double &yaw,
double &vx,
double &vy,
double &vw);
161 void getOdometry(geometry_msgs::Point &odom, geometry_msgs::Twist &odom_vel);
177 OdomMatrix3x1
iterativeLeastSquares(
const OdomMatrix16x3 &lhs,
const OdomMatrix16x1 &rhs,
const int &max_iter);
277 boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::Odometer> >
odometer_publisher_ ;
282 boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::BaseOdometryState> >
state_publisher_ ;
302 boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::OdometryMatrix> >
matrix_publisher_;
303 boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::DebugInfo> >
debug_publisher_;
void publishState()
Publishes the odometry state information.
OdomMatrix16x1 odometry_residual_
ros::Time last_time_
Stores the last update time and the current update time.
ros::Time last_transform_publish_time_
The last time the odometry information was published.
double odometer_publish_rate_
Eigen::Matrix< float, 16, 1 > OdomMatrix16x1
double odom_publish_rate_
double expected_state_publish_time_
The time that the odometry is expected to be published next.
ros::Time last_state_publish_time_
The last time the odometry information was published.
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.
OdomMatrix16x1 fit_residual_
Eigen::Matrix< float, 3, 1 > OdomMatrix3x1
double caster_calibration_multiplier_
double odometry_residual_max_
Maximum residual from the iteritive least squares.
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.
OdomMatrix16x16 weight_matrix_
void update()
(a) Updates positions of the caster and wheels. Called every timestep in realtime ...
void publish()
Publishes the currently computed odometry information.
int ils_max_iterations_
Number of iterations used during iterative least squares.
bool publish_tf_
enable or disable tf publishing
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 getOdometryMessage(nav_msgs::Odometry &msg)
Builds the odometry message and prepares it for sending.
OdomMatrix16x16 findWeightMatrix(const OdomMatrix16x1 &residual)
Finds the weight matrix from the iterative least squares residuals.
std::string odom_frame_
The topic name of the published odometry.
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.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::Odometer > > odometer_publisher_
The RealtimePublisher that does the realtime publishing of the odometry.
std::string base_link_frame_
The topic name of the base link frame.
BaseKinematics base_kin_
class where the robot's information is computed and stored
double odometer_angle_
Total angular distance traveled by the base as computed by the odometer.
geometry_msgs::Twist odom_vel_
Twist that remembers the current translational velocities (vel.vx, vel.vy) and angular position (ang_...
double base_link_floor_z_offset_
Eigen::Matrix< float, 16, 16 > OdomMatrix16x16
~Pr2Odometry()
Destructor for the odometry.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::OdometryMatrix > > matrix_publisher_
geometry_msgs::Point odom_
Point that stores the current translational position (x,y) and angular position (z) ...
boost::scoped_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > transform_publisher_
Publishes the transform between the odometry frame and the base frame.
ros::Time last_publish_time_
The last time the odometry information was published.
double state_publish_rate_
void populateCovariance(const double &residual, nav_msgs::Odometry &msg)
populate the covariance part of the odometry message
ros::Time last_odometer_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
void publishOdometer()
Publishes the currently computed odometer information.
void updateOdometry()
Finds and stores the latest odometry information.
void publishTransform()
Publishes the currently computed odometry information to tf.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::DebugInfo > > debug_publisher_
double getCorrectedWheelSpeed(const int &index)
Computes the wheel's speed adjusted for the attached caster's rotational velocity.
double odometer_distance_
Total distance traveled by the base as computed by the odometer.
Pr2Odometry()
Constructor for the odometry.
void computeBaseVelocity()
Computes the base velocity from the caster positions and wheel speeds.
std::string base_footprint_frame_
The topic name of the base footprint frame.