31 #include <geometry_msgs/Twist.h> 32 #include <geometry_msgs/PoseWithCovarianceStamped.h> 33 #include <nav_msgs/Odometry.h> 60 void cbTwist(
const geometry_msgs::Twist::ConstPtr& msg)
65 void cbInit(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
67 geometry_msgs::PoseStamped pose_in, pose_out;
68 pose_in.header = msg->header;
69 pose_in.pose = msg->pose.pose;
72 geometry_msgs::TransformStamped trans =
82 x_ = pose_out.pose.position.x;
83 y_ = pose_out.pose.position.y;
94 pnh_.
param(
"initial_x", x_, 0.0);
95 pnh_.
param(
"initial_y", y_, 0.0);
96 pnh_.
param(
"initial_yaw", yaw_, 0.0);
100 pub_odom_ = nh_.
advertise<nav_msgs::Odometry>(
"odom", 1,
true);
106 const float dt = 0.01;
116 x_ += cosf(yaw_) * v_ * dt;
117 y_ += sinf(yaw_) * v_ * dt;
119 geometry_msgs::TransformStamped trans;
120 trans.header.stamp = current_time;
121 trans.header.frame_id =
"odom";
122 trans.child_frame_id =
"base_link";
123 trans.transform.translation =
tf2::toMsg(tf2::Vector3(x_, y_, 0.0));
127 nav_msgs::Odometry odom;
128 odom.header.frame_id =
"odom";
129 odom.header.stamp = current_time;
130 odom.child_frame_id =
"base_link";
131 odom.pose.pose.position.x =
x_;
132 odom.pose.pose.position.y =
y_;
134 odom.twist.twist.linear.x =
v_;
135 odom.twist.twist.angular.z =
w_;
141 int main(
int argc,
char* argv[])
void publish(const boost::shared_ptr< M > &message) const
tf2_ros::TransformListener tfl_
void cbInit(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char *argv[])
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
tf2_ros::TransformBroadcaster tfb_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
void cbTwist(const geometry_msgs::Twist::ConstPtr &msg)
ros::Subscriber sub_twist_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double getYaw(const A &a)
ROSCPP_DECL void spinOnce()
ros::Subscriber sub_init_