pr2_odometry.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <Eigen/Core>
36 #include <Eigen/SVD>
37 #include <nav_msgs/Odometry.h>
38 #include <pr2_mechanism_controllers/Odometer.h>
40 #include <tf/tfMessage.h>
41 #include <tf/tf.h>
43 #include <angles/angles.h>
44 
45 #include <boost/scoped_ptr.hpp>
46 
47 #include <std_msgs/Float64.h>
48 #include <pr2_mechanism_controllers/OdometryMatrix.h>
49 #include <pr2_mechanism_controllers/DebugInfo.h>
50 
51 #include <std_msgs/Bool.h>
52 #include <pr2_mechanism_controllers/BaseOdometryState.h>
53 
54 namespace controller
55 {
56 
57 typedef Eigen::Matrix<float, 3, 1> OdomMatrix3x1;
58 typedef Eigen::Matrix<float, 16, 1> OdomMatrix16x1;
59 typedef Eigen::Matrix<float, 16, 3> OdomMatrix16x3;
60 typedef Eigen::Matrix<float, 16, 16> OdomMatrix16x16;
61 
62 
67  {
68  public:
69 
73  Pr2Odometry();
74 
78  ~Pr2Odometry();
79 
86  bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node);
87 
88  /*
89  * \brief The starting method is called by the realtime thread just before
90  * the first call to update. Overrides Controller.staring().
91  * @return Successful start
92  */
93  void starting();
94 
99  void update();
100 
104  void publish();
105 
109  void publishTransform();
110 
114  void publishOdometer();
115 
119  void publishState();
120 
121 
122  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
123 
124  private:
125 
127 
132 
136  void updateOdometry();
137 
142  void getOdometryMessage(nav_msgs::Odometry &msg);
143 
153  void getOdometry(double &x, double &y, double &yaw, double &vx, double &vy, double &vw);
154 
160  void getOdometry(geometry_msgs::Point &odom, geometry_msgs::Twist &odom_vel);
161 
165  void computeBaseVelocity();
166 
171  double getCorrectedWheelSpeed(const int &index);
172 
176  OdomMatrix3x1 iterativeLeastSquares(const OdomMatrix16x3 &lhs, const OdomMatrix16x1 &rhs, const int &max_iter);
177 
181  OdomMatrix16x16 findWeightMatrix(const OdomMatrix16x1 &residual);
182 
187 
192 
197 
201  geometry_msgs::Point odom_;
202 
206  geometry_msgs::Twist odom_vel_;
207 
212 
217 
221  std::string odom_frame_;
222 
226  std::string base_link_frame_;
227 
232 
237 
242 
247 
252 
257 
262 
267 
271  boost::scoped_ptr<realtime_tools::RealtimePublisher <nav_msgs::Odometry> > odometry_publisher_ ;
272 
276  boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::Odometer> > odometer_publisher_ ;
277 
281  boost::scoped_ptr<realtime_tools::RealtimePublisher <pr2_mechanism_controllers::BaseOdometryState> > state_publisher_ ;
282 
286  boost::scoped_ptr<realtime_tools::RealtimePublisher <tf::tfMessage> > transform_publisher_ ;
287 
289 
291 
294 
295 
299  void populateCovariance(const double &residual, nav_msgs::Odometry &msg);
300 
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_;
303 
305 
306  bool isInputValid();
307 
309 
311 
313 
315 
317 
318  OdomMatrix16x3 cbv_lhs_, fit_lhs_;
320  OdomMatrix16x1 fit_rhs_;
321  OdomMatrix16x16 weight_matrix_, w_fit;
322  OdomMatrix3x1 cbv_soln_, fit_soln_;
323 
324  std::string tf_prefix_;
325 
326  };
327 }
void publishState()
Publishes the odometry state information.
OdomMatrix16x1 odometry_residual_
Definition: pr2_odometry.h:319
ros::Time last_time_
Stores the last update time and the current update time.
Definition: pr2_odometry.h:196
ros::Time last_transform_publish_time_
The last time the odometry information was published.
Definition: pr2_odometry.h:241
Eigen::Matrix< float, 16, 1 > OdomMatrix16x1
Definition: pr2_odometry.h:58
OdomMatrix3x1 fit_soln_
Definition: pr2_odometry.h:322
double expected_state_publish_time_
The time that the odometry is expected to be published next.
Definition: pr2_odometry.h:266
ros::Time last_state_publish_time_
The last time the odometry information was published.
Definition: pr2_odometry.h:251
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_
Definition: pr2_odometry.h:319
Eigen::Matrix< float, 3, 1 > OdomMatrix3x1
Definition: pr2_odometry.h:57
OdomMatrix16x1 fit_rhs_
Definition: pr2_odometry.h:320
double caster_calibration_multiplier_
Definition: pr2_odometry.h:316
double odometry_residual_max_
Maximum residual from the iteritive least squares.
Definition: pr2_odometry.h:216
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.
Definition: pr2_odometry.h:256
OdomMatrix16x16 weight_matrix_
Definition: pr2_odometry.h:321
OdomMatrix16x3 fit_lhs_
Definition: pr2_odometry.h:318
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.
Definition: pr2_odometry.h:211
bool publish_tf_
enable or disable tf publishing
Definition: pr2_odometry.h:293
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.
Definition: pr2_odometry.h:221
double expected_odometer_publish_time_
The time that the odometry is expected to be published next.
Definition: pr2_odometry.h:261
boost::scoped_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odometry_publisher_
The RealtimePublisher that does the realtime publishing of the odometry.
Definition: pr2_odometry.h:271
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::Odometer > > odometer_publisher_
The RealtimePublisher that does the realtime publishing of the odometry.
Definition: pr2_odometry.h:276
std::string base_link_frame_
The topic name of the base link frame.
Definition: pr2_odometry.h:226
BaseKinematics base_kin_
class where the robot&#39;s information is computed and stored
Definition: pr2_odometry.h:131
OdomMatrix16x3 cbv_lhs_
Definition: pr2_odometry.h:318
double odometer_angle_
Total angular distance traveled by the base as computed by the odometer.
Definition: pr2_odometry.h:191
geometry_msgs::Twist odom_vel_
Twist that remembers the current translational velocities (vel.vx, vel.vy) and angular position (ang_...
Definition: pr2_odometry.h:206
OdomMatrix3x1 cbv_soln_
Definition: pr2_odometry.h:322
Eigen::Matrix< float, 16, 16 > OdomMatrix16x16
Definition: pr2_odometry.h:60
OdomMatrix16x16 w_fit
Definition: pr2_odometry.h:321
~Pr2Odometry()
Destructor for the odometry.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::OdometryMatrix > > matrix_publisher_
Definition: pr2_odometry.h:301
geometry_msgs::Point odom_
Point that stores the current translational position (x,y) and angular position (z) ...
Definition: pr2_odometry.h:201
boost::scoped_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > transform_publisher_
Publishes the transform between the odometry frame and the base frame.
Definition: pr2_odometry.h:286
ros::Time last_publish_time_
The last time the odometry information was published.
Definition: pr2_odometry.h:236
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.
Definition: pr2_odometry.h:246
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseOdometryState > > state_publisher_
The RealtimePublisher that does the realtime publishing of the odometry state.
Definition: pr2_odometry.h:281
Eigen::Matrix< float, 16, 3 > OdomMatrix16x3
Definition: pr2_odometry.h:59
void publishOdometer()
Publishes the currently computed odometer information.
void updateOdometry()
Finds and stores the latest odometry information.
OdomMatrix16x1 cbv_rhs_
Definition: pr2_odometry.h:319
void publishTransform()
Publishes the currently computed odometry information to tf.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::DebugInfo > > debug_publisher_
Definition: pr2_odometry.h:302
double getCorrectedWheelSpeed(const int &index)
Computes the wheel&#39;s speed adjusted for the attached caster&#39;s rotational velocity.
double odometer_distance_
Total distance traveled by the base as computed by the odometer.
Definition: pr2_odometry.h:186
Pr2Odometry()
Constructor for the odometry.
ros::NodeHandle node_
Definition: pr2_odometry.h:126
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.
Definition: pr2_odometry.h:231


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Sat Nov 12 2022 03:16:31