From d3962147bb3f22cb508b2b6228f246db3905d282 Mon Sep 17 00:00:00 2001 From: Trygve Utstumo Date: Mon, 16 Jun 2014 21:59:51 +0200 Subject: [PATCH 1/7] Updated code to use the twist msg for the turtlesim. --- turtle_teleop/src/teleop_turtle_joy.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/turtle_teleop/src/teleop_turtle_joy.cpp b/turtle_teleop/src/teleop_turtle_joy.cpp index 187b54b..832002f 100644 --- a/turtle_teleop/src/teleop_turtle_joy.cpp +++ b/turtle_teleop/src/teleop_turtle_joy.cpp @@ -1,8 +1,9 @@ // %Tag(FULL)% // %Tag(INCLUDE)% #include -#include +#include #include +#include // %EndTag(INCLUDE)% // %Tag(CLASSDEF)% class TeleopTurtle @@ -34,7 +35,7 @@ TeleopTurtle::TeleopTurtle(): nh_.param("scale_linear", l_scale_, l_scale_); // %EndTag(PARAMS)% // %Tag(PUB)% - vel_pub_ = nh_.advertise("turtle1/command_velocity", 1); + vel_pub_ = nh_.advertise("turtle1/cmd_vel", 1); // %EndTag(PUB)% // %Tag(SUB)% joy_sub_ = nh_.subscribe("joy", 10, &TeleopTurtle::joyCallback, this); @@ -43,10 +44,10 @@ TeleopTurtle::TeleopTurtle(): // %Tag(CALLBACK)% void TeleopTurtle::joyCallback(const sensor_msgs::Joy::ConstPtr& joy) { - turtlesim::Velocity vel; - vel.angular = a_scale_*joy->axes[angular_]; - vel.linear = l_scale_*joy->axes[linear_]; - vel_pub_.publish(vel); + geometry_msgs::Twist twist; + twist.linear.x = l_scale_*joy->axes[linear_]; + twist.angular.z = a_scale_*joy->axes[angular_]; + vel_pub_.publish(twist); } // %EndTag(CALLBACK)% // %Tag(MAIN)% From c1e1ccf8053b0a42a2a83282bfc85635a8eaccff Mon Sep 17 00:00:00 2001 From: Trygve Utstumo Date: Mon, 16 Jun 2014 22:03:23 +0200 Subject: [PATCH 2/7] Added a small Readme --- turtle_teleop/README.md | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 turtle_teleop/README.md diff --git a/turtle_teleop/README.md b/turtle_teleop/README.md new file mode 100644 index 0000000..5639b88 --- /dev/null +++ b/turtle_teleop/README.md @@ -0,0 +1,5 @@ +# Tutorial code for using a Linux Joystick device with ROS + +This code demonstrates how to setup a linux joystick device with ROS and interface it with the turtlesim program. The tutorial text is available on the [ROS Wiki][1]. + +[1]:http://wiki.ros.org/joy/Tutorials/WritingTeleopNode From 06a28a8d3f6b5bed5ad78f24d5bd73c57fa34457 Mon Sep 17 00:00:00 2001 From: Trygve Utstumo Date: Mon, 16 Jun 2014 22:06:22 +0200 Subject: [PATCH 3/7] Moved Readme to top folder --- turtle_teleop/README.md => README.md | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename turtle_teleop/README.md => README.md (100%) diff --git a/turtle_teleop/README.md b/README.md similarity index 100% rename from turtle_teleop/README.md rename to README.md From 4b67ceca749571c321b156ef634027f5f137fde9 Mon Sep 17 00:00:00 2001 From: Trygve Utstumo Date: Mon, 16 Jun 2014 22:08:44 +0200 Subject: [PATCH 4/7] Formatting of readme --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 5639b88..8696990 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,5 @@ -# Tutorial code for using a Linux Joystick device with ROS +### Tutorial code for using a Linux Joystick device with ROS -This code demonstrates how to setup a linux joystick device with ROS and interface it with the turtlesim program. The tutorial text is available on the [ROS Wiki][1]. +This code demonstrates how to setup a linux joystick device with ROS and interface it with the turtlesim program. The tutorial text is available on the ROS Wiki article [Writing a Teleoperation Node for a Linux-Supported Joystick][1]. [1]:http://wiki.ros.org/joy/Tutorials/WritingTeleopNode From 9ce98064f47cf2d1b5ec248dd53f82ccf3f668ed Mon Sep 17 00:00:00 2001 From: Trygve Utstumo Date: Mon, 16 Jun 2014 22:11:32 +0200 Subject: [PATCH 5/7] Removed uneccessary include of turtlesim/Pose.h --- turtle_teleop/src/teleop_turtle_joy.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/turtle_teleop/src/teleop_turtle_joy.cpp b/turtle_teleop/src/teleop_turtle_joy.cpp index 832002f..e4a4690 100644 --- a/turtle_teleop/src/teleop_turtle_joy.cpp +++ b/turtle_teleop/src/teleop_turtle_joy.cpp @@ -3,7 +3,6 @@ #include #include #include -#include // %EndTag(INCLUDE)% // %Tag(CLASSDEF)% class TeleopTurtle From 944ae0244343dada848a72283e30deb180a82bcf Mon Sep 17 00:00:00 2001 From: Trygve Utstumo Date: Mon, 16 Jun 2014 21:59:51 +0200 Subject: [PATCH 6/7] Updated code to use the twist msg for turtlesim, the old turtlesim/Velocity message is removed in Hydro. --- turtle_teleop/src/teleop_turtle_joy.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/turtle_teleop/src/teleop_turtle_joy.cpp b/turtle_teleop/src/teleop_turtle_joy.cpp index 187b54b..e4a4690 100644 --- a/turtle_teleop/src/teleop_turtle_joy.cpp +++ b/turtle_teleop/src/teleop_turtle_joy.cpp @@ -1,7 +1,7 @@ // %Tag(FULL)% // %Tag(INCLUDE)% #include -#include +#include #include // %EndTag(INCLUDE)% // %Tag(CLASSDEF)% @@ -34,7 +34,7 @@ TeleopTurtle::TeleopTurtle(): nh_.param("scale_linear", l_scale_, l_scale_); // %EndTag(PARAMS)% // %Tag(PUB)% - vel_pub_ = nh_.advertise("turtle1/command_velocity", 1); + vel_pub_ = nh_.advertise("turtle1/cmd_vel", 1); // %EndTag(PUB)% // %Tag(SUB)% joy_sub_ = nh_.subscribe("joy", 10, &TeleopTurtle::joyCallback, this); @@ -43,10 +43,10 @@ TeleopTurtle::TeleopTurtle(): // %Tag(CALLBACK)% void TeleopTurtle::joyCallback(const sensor_msgs::Joy::ConstPtr& joy) { - turtlesim::Velocity vel; - vel.angular = a_scale_*joy->axes[angular_]; - vel.linear = l_scale_*joy->axes[linear_]; - vel_pub_.publish(vel); + geometry_msgs::Twist twist; + twist.linear.x = l_scale_*joy->axes[linear_]; + twist.angular.z = a_scale_*joy->axes[angular_]; + vel_pub_.publish(twist); } // %EndTag(CALLBACK)% // %Tag(MAIN)% From 3a226a322764a10a5e276438b970005033f5b7f7 Mon Sep 17 00:00:00 2001 From: Trygve Utstumo Date: Mon, 16 Jun 2014 22:03:23 +0200 Subject: [PATCH 7/7] Added a small Readme --- README.md | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 README.md diff --git a/README.md b/README.md new file mode 100644 index 0000000..8696990 --- /dev/null +++ b/README.md @@ -0,0 +1,5 @@ +### Tutorial code for using a Linux Joystick device with ROS + +This code demonstrates how to setup a linux joystick device with ROS and interface it with the turtlesim program. The tutorial text is available on the ROS Wiki article [Writing a Teleoperation Node for a Linux-Supported Joystick][1]. + +[1]:http://wiki.ros.org/joy/Tutorials/WritingTeleopNode