GraftOdometryTopic.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Chad Rockey
32  */
33 
35 
37  absolute_pose_(false), delta_pose_(false), use_velocities_(false), timeout_(1.0)
38 {
39  for( int i=0; i<36; i++ ) {
40  pose_covariance_[i] = 0.0;
41  twist_covariance_[i] = 0.0;
42  }
43 }
44 
45 
47 {
48 }
49 
50 
51 void GraftOdometryTopic::callback(const nav_msgs::Odometry::ConstPtr& msg)
52 {
53  msg_ = msg;
54 }
55 
56 
57 void GraftOdometryTopic::setName(const std::string& name)
58 {
59  name_ = name;
60 }
61 
62 
64 {
65  return name_;
66 }
67 
68 
70 {
71  msg_ = nav_msgs::Odometry::ConstPtr();
72 }
73 
74 
75 geometry_msgs::Twist::Ptr twistFromPoses(
76  const geometry_msgs::Pose& pose,
77  const geometry_msgs::Pose& last_pose,
78  const double dt)
79 {
80  geometry_msgs::Twist::Ptr out(new geometry_msgs::Twist());
81 
82  if (dt < 1e-10)
83  {
84  return out;
85  }
86 
87  tf::Quaternion tfq2, tfq1;
88  tf::quaternionMsgToTF(pose.orientation, tfq2);
89  tf::quaternionMsgToTF(last_pose.orientation, tfq1);
90  tf::Transform tf2(tfq2, tf::Vector3(pose.position.x, pose.position.y, pose.position.z));
91  tf::Transform tf1(tfq1, tf::Vector3(last_pose.position.x, last_pose.position.y, last_pose.position.z));
92 
93  tf::Transform dtf = tf1.inverse() * tf2;
94 
95  out->linear.x = dtf.getOrigin().getX()/dt;
96  out->linear.y = dtf.getOrigin().getY()/dt;
97  out->linear.y = dtf.getOrigin().getZ()/dt;
98  double rX, rY, rZ;
99  dtf.getBasis().getEulerYPR(rZ, rY, rX);
100  out->angular.x = rX/dt;
101  out->angular.y = rY/dt;
102  out->angular.z = rZ/dt;
103 
104  return out;
105 }
106 
107 
108 graft::GraftSensorResidual::Ptr GraftOdometryTopic::h(const graft::GraftState& state)
109 {
110  graft::GraftSensorResidual::Ptr out(new graft::GraftSensorResidual());
111  out->header = state.header;
112  out->name = name_;
113  out->pose = state.pose;
114  out->twist = state.twist;
115  return out;
116 }
117 
118 
119 graft::GraftSensorResidual::Ptr GraftOdometryTopic::z()
120 {
121  if (msg_ == NULL || ros::Time::now() - timeout_ > msg_->header.stamp)
122  {
123  ROS_WARN_THROTTLE(5.0, "%s (Odometry) timeout", name_.c_str());
124  return graft::GraftSensorResidual::Ptr();
125  }
126 
127  graft::GraftSensorResidual::Ptr out(new graft::GraftSensorResidual());
128  out->header = msg_->header;
129  out->name = name_;
130 
131  if (delta_pose_)
132  {
133  if (last_msg_ == NULL)
134  {
135  last_msg_ = msg_;
136  return graft::GraftSensorResidual::Ptr();
137  }
138  double dt = (msg_->header.stamp - last_msg_->header.stamp).toSec();
139  out->twist = *twistFromPoses(msg_->pose.pose, last_msg_->pose.pose, dt);
140  last_msg_ = msg_;
141  if (std::accumulate(twist_covariance_.begin(),twist_covariance_.end(),0.0) > 1e-15)
142  {
143  // Override message
144  out->twist_covariance = twist_covariance_;
145  }
146  else
147  {
148  // Use from message
149  // Not sure what to do about covariance here...... robot_pose_ekf was strange
150  out->twist_covariance = msg_->pose.covariance;
151  }
152  }
153  else if(use_velocities_)
154  {
155  out->twist = msg_->twist.twist;
156  if (std::accumulate(twist_covariance_.begin(),twist_covariance_.end(),0.0) > 1e-15)
157  {
158  // Override message
159  out->twist_covariance = twist_covariance_;
160  }
161  else
162  {
163  // Use from message
164  out->twist_covariance = msg_->twist.covariance;
165  }
166  }
167 
168  if (absolute_pose_ && !delta_pose_) // Delta Pose and Absolute Pose are incompatible
169  {
170  out->pose = msg_->pose.pose;
171  if (std::accumulate(pose_covariance_.begin(),pose_covariance_.end(),0.0) > 1e-15)
172  {
173  // Override message
174  out->pose_covariance = pose_covariance_;
175  }
176  else
177  {
178  // Use from message
179  out->pose_covariance = msg_->pose.covariance;
180  }
181  }
182  return out;
183 }
184 
185 
186 void GraftOdometryTopic::setTimeout(double timeout)
187 {
188  if (timeout < 1e-10)
189  {
190  timeout_ = ros::Duration(1e10); // No timeout enforced
191  return;
192  }
193  timeout_ = ros::Duration(timeout);
194 }
195 
196 
197 void GraftOdometryTopic::setPoseCovariance(boost::array<double, 36>& cov)
198 {
199  pose_covariance_ = cov;
200 }
201 
202 
203 void GraftOdometryTopic::setTwistCovariance(boost::array<double, 36>& cov)
204 {
205  twist_covariance_ = cov;
206 }
207 
208 
209 void GraftOdometryTopic::useAbsolutePose(bool absolute_pose)
210 {
211  absolute_pose_ = absolute_pose;
212 }
213 
214 
215 void GraftOdometryTopic::useDeltaPose(bool delta_pose)
216 {
217  delta_pose_ = delta_pose;
218 }
219 
220 
221 void GraftOdometryTopic::useVelocities(bool use_velocities)
222 {
223  use_velocities_ = use_velocities;
224 }
225 
226 
227 nav_msgs::Odometry::ConstPtr GraftOdometryTopic::getMsg()
228 {
229  return msg_;
230 }
GraftOdometryTopic::useDeltaPose
void useDeltaPose(bool delta_pose)
Definition: GraftOdometryTopic.cpp:215
GraftOdometryTopic::getName
virtual std::string getName()
Definition: GraftOdometryTopic.cpp:63
twistFromPoses
geometry_msgs::Twist::Ptr twistFromPoses(const geometry_msgs::Pose &pose, const geometry_msgs::Pose &last_pose, const double dt)
Definition: GraftOdometryTopic.cpp:75
GraftOdometryTopic::GraftOdometryTopic
GraftOdometryTopic()
Definition: GraftOdometryTopic.cpp:36
GraftOdometryTopic::z
virtual graft::GraftSensorResidual::Ptr z()
Definition: GraftOdometryTopic.cpp:119
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
GraftOdometryTopic::useAbsolutePose
void useAbsolutePose(bool absolute_pose)
Definition: GraftOdometryTopic.cpp:209
tf::quaternionMsgToTF
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
GraftOdometryTopic::callback
void callback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: GraftOdometryTopic.cpp:51
tf::Transform::getBasis
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
GraftOdometryTopic::absolute_pose_
bool absolute_pose_
Definition: GraftOdometryTopic.h:91
tf::Transform::inverse
Transform inverse() const
GraftOdometryTopic::setName
virtual void setName(const std::string &name)
Definition: GraftOdometryTopic.cpp:57
GraftOdometryTopic::getMsg
nav_msgs::Odometry::ConstPtr getMsg()
Definition: GraftOdometryTopic.cpp:227
GraftOdometryTopic.h
tf::Transform
GraftOdometryTopic::twist_covariance_
boost::array< double, 36 > twist_covariance_
Definition: GraftOdometryTopic.h:97
GraftOdometryTopic::name_
std::string name_
Definition: GraftOdometryTopic.h:90
GraftOdometryTopic::useVelocities
void useVelocities(bool use_velocities)
Definition: GraftOdometryTopic.cpp:221
tf::Matrix3x3::getEulerYPR
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
GraftOdometryTopic::setPoseCovariance
void setPoseCovariance(boost::array< double, 36 > &cov)
Definition: GraftOdometryTopic.cpp:197
GraftOdometryTopic::delta_pose_
bool delta_pose_
Definition: GraftOdometryTopic.h:92
GraftOdometryTopic::pose_covariance_
boost::array< double, 36 > pose_covariance_
Definition: GraftOdometryTopic.h:96
GraftOdometryTopic::~GraftOdometryTopic
~GraftOdometryTopic()
Definition: GraftOdometryTopic.cpp:46
GraftOdometryTopic::timeout_
ros::Duration timeout_
Definition: GraftOdometryTopic.h:94
tf2
GraftOdometryTopic::h
virtual graft::GraftSensorResidual::Ptr h(const graft::GraftState &state)
Definition: GraftOdometryTopic.cpp:108
GraftOdometryTopic::msg_
nav_msgs::Odometry::ConstPtr msg_
Definition: GraftOdometryTopic.h:87
GraftOdometryTopic::setTimeout
void setTimeout(double timeout)
Definition: GraftOdometryTopic.cpp:186
GraftOdometryTopic::use_velocities_
bool use_velocities_
Definition: GraftOdometryTopic.h:93
ros::Duration
GraftOdometryTopic::setTwistCovariance
void setTwistCovariance(boost::array< double, 36 > &cov)
Definition: GraftOdometryTopic.cpp:203
tf::Quaternion
tf::Transform::getOrigin
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
GraftOdometryTopic::last_msg_
nav_msgs::Odometry::ConstPtr last_msg_
Definition: GraftOdometryTopic.h:88
GraftOdometryTopic::clearMessage
virtual void clearMessage()
Definition: GraftOdometryTopic.cpp:69
ros::Time::now
static Time now()


graft
Author(s): Chad Rockey
autogenerated on Wed Mar 2 2022 00:20:33