GraftImuTopic.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 
34 #include <graft/GraftImuTopic.h>
35 
36 
38 {
39  for( int i=0; i<9; i++ ) {
40  orientation_covariance_[i] = 0.0;
43  }
44 }
45 
46 
48 {
49 }
50 
51 
52 void GraftImuTopic::callback(const sensor_msgs::Imu::ConstPtr& msg)
53 {
54  msg_ = msg;
55 }
56 
57 
58 void GraftImuTopic::setName(const std::string& name)
59 {
60  name_ = name;
61 }
62 
64 {
65  return name_;
66 }
67 
69 {
70  msg_ = sensor_msgs::Imu::ConstPtr();
71 }
72 
73 geometry_msgs::Twist::Ptr twistFromQuaternions(
74  const geometry_msgs::Quaternion& quat,
75  const geometry_msgs::Quaternion& last_quat,
76  const double dt)
77 {
78  geometry_msgs::Twist::Ptr out(new geometry_msgs::Twist());
79 
80  if (dt < 1e-10)
81  {
82  return out;
83  }
84 
85  tf::Quaternion tfq2, tfq1;
86  tf::quaternionMsgToTF(quat, tfq2);
87  tf::quaternionMsgToTF(last_quat, tfq1);
88  tf::Transform tf2(tfq2, tf::Vector3(0, 0, 0));
89  tf::Transform tf1(tfq1, tf::Vector3(0, 0, 0));
90 
91  tf::Transform dtf = tf1.inverse() * tf2;
92 
93  out->linear.x = 0;
94  out->linear.y = 0;
95  out->linear.y = 0;
96  double rX, rY, rZ;
97  dtf.getBasis().getEulerYPR(rZ, rY, rX);
98  out->angular.x = rX/dt;
99  out->angular.y = rY/dt;
100  out->angular.z = rZ/dt;
101 
102  return out;
103 }
104 
105 
106 geometry_msgs::Vector3 accelFromQuaternion(
107  const geometry_msgs::Quaternion& q,
108  const double gravity_magnitude)
109 {
110  geometry_msgs::Vector3 out;
111  if (q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w > 1e-10)
112  {
113  tf::Quaternion tfq;
114  tf::quaternionMsgToTF(q, tfq);
115  tf::Transform tft(tfq, tf::Vector3(0, 0, 0));
116  tf::Vector3 gravity(0, 0, gravity_magnitude);
117  tf::vector3TFToMsg(tft.inverse()*gravity, out);
118  }
119  return out;
120 }
121 
122 
123 graft::GraftSensorResidual::Ptr GraftImuTopic::h(const graft::GraftState& state)
124 {
125  graft::GraftSensorResidual::Ptr out(new graft::GraftSensorResidual());
126  out->header = state.header;
127  out->name = name_;
128  out->pose = state.pose;
129  out->twist = state.twist;
130  out->accel = accelFromQuaternion(state.pose.orientation, 9.81);
131  return out;
132 }
133 
134 
135 boost::array<double, 36> largeCovarianceFromSmallCovariance(
136  const boost::array<double, 9>& angular_velocity_covariance)
137 {
138  boost::array<double, 36> out;
139  for (size_t i = 0; i < out.size(); i++)
140  {
141  out[i] = 0;
142  }
143  for (size_t i = 0; i < 3; i++)
144  {
145  out[i+21] = angular_velocity_covariance[i];
146  }
147  for (size_t i = 3; i < 6; i++)
148  {
149  out[i+24] = angular_velocity_covariance[i];
150  }
151  for (size_t i = 6; i < 9; i++)
152  {
153  out[i+27] = angular_velocity_covariance[i];
154  }
155  return out;
156 }
157 
158 graft::GraftSensorResidual::Ptr GraftImuTopic::z()
159 {
160  if (msg_ == NULL || ros::Time::now() - timeout_ > msg_->header.stamp)
161  {
162  ROS_WARN_THROTTLE(5.0, "%s (IMU) timeout", name_.c_str());
163  return graft::GraftSensorResidual::Ptr();
164  }
165 
166  graft::GraftSensorResidual::Ptr out(new graft::GraftSensorResidual());
167  out->header = msg_->header;
168  out->name = name_;
169 
170  if (delta_orientation_)
171  {
172  if (last_msg_ == NULL)
173  {
174  last_msg_ = msg_;
175  return graft::GraftSensorResidual::Ptr();
176  }
177  double dt = (msg_->header.stamp - last_msg_->header.stamp).toSec();
178  out->twist = *twistFromQuaternions(msg_->orientation, last_msg_->orientation, dt);
179  last_msg_ = msg_;
180  if (std::accumulate(angular_velocity_covariance_.begin(),angular_velocity_covariance_.end(),0.0) > 1e-15)
181  {
182  // Override message
184  }
185  else
186  {
187  // Use from message
188  // Not sure what to do about covariance here...... robot_pose_ekf was strange
189  out->twist_covariance = largeCovarianceFromSmallCovariance(msg_->orientation_covariance);
190  }
191  out->twist_covariance[35] = msg_->orientation_covariance[8];
192  }
193  else
194  {
195  out->pose.orientation = msg_->orientation;
196  out->twist.angular = msg_->angular_velocity;
197  if (std::accumulate(orientation_covariance_.begin(),orientation_covariance_.end(),0.0) > 1e-15)
198  {
199  // Override message
201  }
202  else
203  {
204  // Use from message
205  out->pose_covariance = largeCovarianceFromSmallCovariance(msg_->orientation_covariance);
206  }
207  if (std::accumulate(angular_velocity_covariance_.begin(),angular_velocity_covariance_.end(),0.0) > 1e-15)
208  {
209  // Override message
211  }
212  else
213  {
214  // Use from message
215  out->twist_covariance = largeCovarianceFromSmallCovariance(msg_->angular_velocity_covariance);
216  }
217  }
218 
219  out->accel = msg_->linear_acceleration;
220  if (std::accumulate(linear_acceleration_covariance_.begin(),linear_acceleration_covariance_.end(),0.0) > 1e-15)
221  {
222  // Override message
223  out->accel_covariance = linear_acceleration_covariance_;
224  }
225  else
226  {
227  // Use from message
228  out->accel_covariance = msg_->linear_acceleration_covariance;
229  }
230  return out;
231 }
232 
233 
234 void GraftImuTopic::useDeltaOrientation(bool delta_orientation)
235 {
236  delta_orientation_ = delta_orientation;
237 }
238 
239 
240 void GraftImuTopic::setTimeout(double timeout)
241 {
242  if (timeout < 1e-10)
243  {
244  timeout_ = ros::Duration(1e10); // No timeout enforced
245  return;
246  }
247  timeout_ = ros::Duration(timeout);
248 }
249 
250 
251 void GraftImuTopic::setOrientationCovariance(boost::array<double, 9>& cov)
252 {
254 }
255 
256 
257 void GraftImuTopic::setAngularVelocityCovariance(boost::array<double, 9>& cov)
258 {
260 }
261 
262 
263 void GraftImuTopic::setLinearAccelerationCovariance(boost::array<double, 9>& cov)
264 {
266 }
267 
268 
269 sensor_msgs::Imu::ConstPtr GraftImuTopic::getMsg()
270 {
271  return msg_;
272 }
GraftImuTopic::setTimeout
void setTimeout(double timeout)
Definition: GraftImuTopic.cpp:240
GraftImuTopic::setLinearAccelerationCovariance
void setLinearAccelerationCovariance(boost::array< double, 9 > &cov)
Definition: GraftImuTopic.cpp:263
GraftImuTopic::last_msg_
sensor_msgs::Imu::ConstPtr last_msg_
Definition: GraftImuTopic.h:93
GraftImuTopic::GraftImuTopic
GraftImuTopic()
Definition: GraftImuTopic.cpp:37
GraftImuTopic::msg_
sensor_msgs::Imu::ConstPtr msg_
Definition: GraftImuTopic.h:92
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
tf::quaternionMsgToTF
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
GraftImuTopic::z
virtual graft::GraftSensorResidual::Ptr z()
Definition: GraftImuTopic.cpp:158
GraftImuTopic::linear_acceleration_covariance_
boost::array< double, 9 > linear_acceleration_covariance_
Definition: GraftImuTopic.h:104
tf::Transform::getBasis
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
largeCovarianceFromSmallCovariance
boost::array< double, 36 > largeCovarianceFromSmallCovariance(const boost::array< double, 9 > &angular_velocity_covariance)
Definition: GraftImuTopic.cpp:135
GraftImuTopic::setName
virtual void setName(const std::string &name)
Definition: GraftImuTopic.cpp:58
GraftImuTopic::orientation_covariance_
boost::array< double, 9 > orientation_covariance_
Definition: GraftImuTopic.h:102
GraftImuTopic.h
GraftImuTopic::~GraftImuTopic
~GraftImuTopic()
Definition: GraftImuTopic.cpp:47
GraftImuTopic::angular_velocity_covariance_
boost::array< double, 9 > angular_velocity_covariance_
Definition: GraftImuTopic.h:103
GraftImuTopic::h
virtual graft::GraftSensorResidual::Ptr h(const graft::GraftState &state)
Definition: GraftImuTopic.cpp:123
tf::Transform::inverse
Transform inverse() const
GraftImuTopic::getMsg
sensor_msgs::Imu::ConstPtr getMsg()
Definition: GraftImuTopic.cpp:269
GraftImuTopic::clearMessage
virtual void clearMessage()
Definition: GraftImuTopic.cpp:68
GraftImuTopic::delta_orientation_
bool delta_orientation_
Definition: GraftImuTopic.h:97
GraftImuTopic::callback
void callback(const sensor_msgs::Imu::ConstPtr &msg)
Definition: GraftImuTopic.cpp:52
tf::Transform
GraftImuTopic::timeout_
ros::Duration timeout_
Definition: GraftImuTopic.h:100
GraftImuTopic::setAngularVelocityCovariance
void setAngularVelocityCovariance(boost::array< double, 9 > &cov)
Definition: GraftImuTopic.cpp:257
tf::Matrix3x3::getEulerYPR
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
twistFromQuaternions
geometry_msgs::Twist::Ptr twistFromQuaternions(const geometry_msgs::Quaternion &quat, const geometry_msgs::Quaternion &last_quat, const double dt)
Definition: GraftImuTopic.cpp:73
GraftImuTopic::setOrientationCovariance
void setOrientationCovariance(boost::array< double, 9 > &cov)
Definition: GraftImuTopic.cpp:251
GraftImuTopic::useDeltaOrientation
void useDeltaOrientation(bool delta_orientation)
Definition: GraftImuTopic.cpp:234
accelFromQuaternion
geometry_msgs::Vector3 accelFromQuaternion(const geometry_msgs::Quaternion &q, const double gravity_magnitude)
Definition: GraftImuTopic.cpp:106
tf2
tf::vector3TFToMsg
static void vector3TFToMsg(const Vector3 &bt_v, geometry_msgs::Vector3 &msg_v)
ros::Duration
tf::Quaternion
GraftImuTopic::name_
std::string name_
Definition: GraftImuTopic.h:95
GraftImuTopic::getName
virtual std::string getName()
Definition: GraftImuTopic.cpp:63
ros::Time::now
static Time now()


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