39 for(
int i=0; i<9; i++ ) {
70 msg_ = sensor_msgs::Imu::ConstPtr();
74 const geometry_msgs::Quaternion& quat,
75 const geometry_msgs::Quaternion& last_quat,
78 geometry_msgs::Twist::Ptr out(
new geometry_msgs::Twist());
98 out->angular.x = rX/dt;
99 out->angular.y = rY/dt;
100 out->angular.z = rZ/dt;
107 const geometry_msgs::Quaternion& q,
108 const double gravity_magnitude)
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)
116 tf::Vector3 gravity(0, 0, gravity_magnitude);
125 graft::GraftSensorResidual::Ptr out(
new graft::GraftSensorResidual());
126 out->header = state.header;
128 out->pose = state.pose;
129 out->twist = state.twist;
136 const boost::array<double, 9>& angular_velocity_covariance)
138 boost::array<double, 36> out;
139 for (
size_t i = 0; i < out.size(); i++)
143 for (
size_t i = 0; i < 3; i++)
145 out[i+21] = angular_velocity_covariance[i];
147 for (
size_t i = 3; i < 6; i++)
149 out[i+24] = angular_velocity_covariance[i];
151 for (
size_t i = 6; i < 9; i++)
153 out[i+27] = angular_velocity_covariance[i];
163 return graft::GraftSensorResidual::Ptr();
166 graft::GraftSensorResidual::Ptr out(
new graft::GraftSensorResidual());
167 out->header =
msg_->header;
175 return graft::GraftSensorResidual::Ptr();
177 double dt = (
msg_->header.stamp -
last_msg_->header.stamp).toSec();
191 out->twist_covariance[35] =
msg_->orientation_covariance[8];
195 out->pose.orientation =
msg_->orientation;
196 out->twist.angular =
msg_->angular_velocity;
219 out->accel =
msg_->linear_acceleration;
228 out->accel_covariance =
msg_->linear_acceleration_covariance;