Go to the documentation of this file.
62 std::string prefix_param;
68 node.
param<
double>(
"odom/initial_x",
odom_.x, 0.0);
69 node.param<
double>(
"odom/initial_y",
odom_.y, 0.0);
70 node.param<
double>(
"odom/initial_yaw",
odom_.z, 0.0);
74 node.param<std::string> (
"odom_frame",
odom_frame_,
"odom");
79 node.param<
double> (
"x_stddev",
sigma_x_, 0.002);
80 node.param<
double> (
"y_stddev",
sigma_y_, 0.002);
83 node.param<
double> (
"cov_xy",
cov_x_y_, 0.0);
91 node.param<
double>(
"caster_calibration_multiplier",
125 ROS_ERROR(
"The Base odometry could not start because the casters were "
126 "not calibrated. Relaunch the odometry after you see the caster "
127 "calibration finish.");
234 double theta =
odom_.z;
235 double costh = cos(theta);
236 double sinth = sin(theta);
240 double odom_delta_x = (
odom_vel_.linear.x * costh -
242 double odom_delta_y = (
odom_vel_.linear.x * sinth +
244 double odom_delta_th =
odom_vel_.angular.z * dt;
246 odom_.x += odom_delta_x;
247 odom_.y += odom_delta_y;
248 odom_.z += odom_delta_th;
253 odom_delta_y * odom_delta_y);
258 geometry_msgs::Twist &odom_vel)
271 msg.pose.pose.position.z = 0.0;
275 msg.pose.pose.orientation.x = quat_trans.x();
276 msg.pose.pose.orientation.y = quat_trans.y();
277 msg.pose.pose.orientation.z = quat_trans.z();
278 msg.pose.pose.orientation.w = quat_trans.w();
285 nav_msgs::Odometry &msg)
287 double odom_multiplier = 1.0;
293 msg.pose.covariance[0] = 1e-12;
294 msg.pose.covariance[7] = 1e-12;
295 msg.pose.covariance[35] = 1e-12;
297 msg.pose.covariance[1] = 1e-12;
298 msg.pose.covariance[6] = 1e-12;
300 msg.pose.covariance[31] = 1e-12;
301 msg.pose.covariance[11] = 1e-12;
303 msg.pose.covariance[30] = 1e-12;
304 msg.pose.covariance[5] = 1e-12;
307 msg.pose.covariance[0] = odom_multiplier*pow(
sigma_x_,2);
308 msg.pose.covariance[7] = odom_multiplier*pow(
sigma_y_,2);
321 msg.pose.covariance[14] = DBL_MAX;
322 msg.pose.covariance[21] = DBL_MAX;
323 msg.pose.covariance[28] = DBL_MAX;
325 msg.twist.covariance =
msg.pose.covariance;
330 double &vx,
double &vy,
double &vw)
342 double steer_angle, wheel_speed, costh, sinth;
343 geometry_msgs::Twist caster_local_velocity;
344 geometry_msgs::Twist wheel_local_velocity;
345 geometry_msgs::Point wheel_position;
350 costh = cos(steer_angle);
351 sinth = sin(steer_angle);
354 ROS_DEBUG(
"Odometry:: Wheel: %s, angle: %f, speed: %f",
362 sinth * wheel_position.x;
365 cbv_lhs_(i * 2 + 1, 2) = sinth * wheel_position.y +
366 costh * wheel_position.x;
383 geometry_msgs::Twist caster_local_vel;
384 geometry_msgs::Twist wheel_local_vel;
396 double svd_time = 0.0;
397 bool pub_matrix =
false;
400 for(
int i = 0;
i < max_iter;
i++) {
406 Eigen::JacobiSVD<Eigen::MatrixXf> svdOfFit(
fit_lhs_,Eigen::ComputeThinU|Eigen::ComputeThinV);
409 ROS_DEBUG(
"Odometry:: fit_soln_: %f %f %f",
416 for(
int k = 0;
k < 48;
k++) {
418 int j_index =
k - i_index *3;
432 ROS_DEBUG(
"Breaking out since odometry looks good");
455 double g_sigma = 0.1;
458 w_fit(i, i) = sqrt(exp(-pow(residual(i, 0), 2) /
459 (2 * g_sigma * g_sigma) ));
518 double x(0.), y(0.0), yaw(0.0), vx(0.0), vy(0.0), vyaw(0.0);
521 geometry_msgs::TransformStamped &out =
527 out.transform.translation.x = -x * cos(yaw) - y * sin(yaw);
528 out.transform.translation.y = +x * sin(yaw) - y * cos(yaw);
529 out.transform.translation.z = 0;
533 out.transform.rotation.x = quat_trans.x();
534 out.transform.rotation.y = quat_trans.y();
535 out.transform.rotation.z = quat_trans.z();
536 out.transform.rotation.w = quat_trans.w();
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.
const static double MAX_ALLOWABLE_SVD_TIME
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.
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
BaseKinematics base_kin_
class where the robot's information is computed and stored
bool getParam(const std::string &key, bool &b) const
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
std::string resolve(const std::string &prefix, const std::string &frame_name)
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)
std::vector< Caster > caster_
vector of every caster attached to the base
ros::Time last_odometer_publish_time_
The last time the odometry information was published.
std::vector< Wheel > wheel_
vector of every wheel attached to the base
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_
int num_wheels_
number of wheels connected to the base
double odom_publish_rate_
geometry_msgs::Twist odom_vel_
Twist that remembers the current translational velocities (vel.vx, vel.vy) and angular position (ang_...
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...
bool searchParam(const std::string &key, std::string &result) const
double state_publish_rate_
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
OdomMatrix16x16 findWeightMatrix(const OdomMatrix16x1 &residual)
Finds the weight matrix from the iterative least squares residuals.
void publishOdometer()
Publishes the currently computed odometer information.
const static double ODOMETRY_THRESHOLD
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.
pr2_mechanism_model::RobotState * robot_state_
remembers everything about the state of the robot
Eigen::Matrix< float, 16, 1 > OdomMatrix16x1
void computeBaseVelocity()
Computes the base velocity from the caster positions and wheel speeds.
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.
T param(const std::string ¶m_name, const T &default_val) const
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.
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
Loads BaseKinematic's information from the xml description file and param server.
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_
int num_casters_
number of casters connected to the base
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.