tutorials
mimic.cpp
Go to the documentation of this file.
1
#include <
ros/ros.h
>
2
#include <turtlesim/Pose.h>
3
#include <geometry_msgs/Twist.h>
4
5
class
Mimic
6
{
7
public
:
8
Mimic
();
9
10
private
:
11
void
poseCallback
(
const
turtlesim::PoseConstPtr& pose);
12
13
ros::Publisher
twist_pub_
;
14
ros::Subscriber
pose_sub_
;
15
};
16
17
Mimic::Mimic
()
18
{
19
ros::NodeHandle
input_nh(
"input"
);
20
ros::NodeHandle
output_nh(
"output"
);
21
twist_pub_
= output_nh.
advertise
<geometry_msgs::Twist>(
"cmd_vel"
, 1);
22
pose_sub_
= input_nh.
subscribe
<turtlesim::Pose>(
"pose"
, 1, &
Mimic::poseCallback
,
this
);
23
}
24
25
void
Mimic::poseCallback
(
const
turtlesim::PoseConstPtr& pose)
26
{
27
geometry_msgs::Twist twist;
28
twist.angular.z = pose->angular_velocity;
29
twist.linear.x = pose->linear_velocity;
30
twist_pub_
.
publish
(twist);
31
}
32
33
int
main
(
int
argc,
char
** argv)
34
{
35
ros::init
(argc, argv,
"turtle_mimic"
);
36
Mimic
mimic;
37
38
ros::spin
();
39
}
40
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
Mimic::poseCallback
void poseCallback(const turtlesim::PoseConstPtr &pose)
Definition:
mimic.cpp:25
ros.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
Mimic::Mimic
Mimic()
Definition:
mimic.cpp:17
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
Mimic::twist_pub_
ros::Publisher twist_pub_
Definition:
mimic.cpp:13
Mimic::pose_sub_
ros::Subscriber pose_sub_
Definition:
mimic.cpp:14
main
int main(int argc, char **argv)
Definition:
mimic.cpp:33
ros::spin
ROSCPP_DECL void spin()
Mimic
Definition:
mimic.cpp:5
ros::NodeHandle
ros::Subscriber
turtlesim
Author(s): Josh Faust, Dirk Thomas
autogenerated on Sat Apr 12 2025 02:28:03