37 absolute_pose_(false), delta_pose_(false), use_velocities_(false), timeout_(1.0)
39 for(
int i=0; i<36; i++ ) {
71 msg_ = nav_msgs::Odometry::ConstPtr();
76 const geometry_msgs::Pose& pose,
77 const geometry_msgs::Pose& last_pose,
80 geometry_msgs::Twist::Ptr out(
new geometry_msgs::Twist());
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));
95 out->linear.x = dtf.
getOrigin().getX()/dt;
96 out->linear.y = dtf.
getOrigin().getY()/dt;
97 out->linear.y = dtf.
getOrigin().getZ()/dt;
100 out->angular.x = rX/dt;
101 out->angular.y = rY/dt;
102 out->angular.z = rZ/dt;
110 graft::GraftSensorResidual::Ptr out(
new graft::GraftSensorResidual());
111 out->header = state.header;
113 out->pose = state.pose;
114 out->twist = state.twist;
124 return graft::GraftSensorResidual::Ptr();
127 graft::GraftSensorResidual::Ptr out(
new graft::GraftSensorResidual());
128 out->header =
msg_->header;
136 return graft::GraftSensorResidual::Ptr();
138 double dt = (
msg_->header.stamp -
last_msg_->header.stamp).toSec();
150 out->twist_covariance =
msg_->pose.covariance;
155 out->twist =
msg_->twist.twist;
164 out->twist_covariance =
msg_->twist.covariance;
170 out->pose =
msg_->pose.pose;
179 out->pose_covariance =
msg_->pose.covariance;