35 #include <Eigen/Dense>
42 #include <graft/GraftState.h>
60 geometry_msgs::TransformStamped
tf;
61 tf.header.stamp = msg.header.stamp;
62 tf.header.frame_id = msg.header.frame_id;
63 tf.child_frame_id = msg.child_frame_id;
65 tf.transform.translation.x = msg.pose.pose.position.x;
66 tf.transform.translation.y = msg.pose.pose.position.y;
67 tf.transform.translation.z = msg.pose.pose.position.z;
68 tf.transform.rotation = msg.pose.pose.orientation;
84 odom_.pose.pose = state.pose;
85 odom_.twist.twist = state.twist;
92 int main(
int argc,
char **argv)
94 ros::init(argc, argv,
"graft_ukf_velocity");
101 std::vector<boost::shared_ptr<GraftSensor> > topics;
102 std::vector<ros::Subscriber> subs;
121 odom_.pose.pose.position.x = 0.0;
122 odom_.pose.pose.position.y = 0.0;
123 odom_.pose.pose.position.z = 0.0;
125 odom_.pose.pose.orientation.w = 1.0;
126 odom_.pose.pose.orientation.x = 0.0;
127 odom_.pose.pose.orientation.y = 0.0;
128 odom_.pose.pose.orientation.z = 0.0;
130 odom_.twist.twist.linear.x = 0.0;
131 odom_.twist.twist.linear.y = 0.0;
132 odom_.twist.twist.linear.z = 0.0;
133 odom_.twist.twist.angular.x = 0.0;
134 odom_.twist.twist.angular.y = 0.0;
135 odom_.twist.twist.angular.z = 0.0;