ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Subscribe to geometry_msgs/Pose2D message for arduino application

asked 2015-08-03 21:34:03 -0500

rosdino gravatar image

updated 2016-10-24 09:03:52 -0500

ngrennan gravatar image

Hello everyone,

How to subscribe to geometry_msgs/Pose2D type message for an arduino application? Any example?

Thanks in advance.

Any help?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2015-08-04 21:47:47 -0500

Here is a simple example that subscribes to a geometry_msgs/Pose2D topic, toggles a LED every time it receives a message and stores the data in separate variables.

#include <ros.h>
#include <geometry_msgs/Pose2D.h>

ros::NodeHandle  nh;

void poseCb( const geometry_msgs::Pose2D& pose_msg){
  digitalWrite(13, HIGH-digitalRead(13));   // blink the led
  float x = pose_msg.x;
  float y = pose_msg.y;
  float th = pose_msg.theta;
}

ros::Subscriber<geometry_msgs::Pose2D> sub("pose", &poseCb );

void setup()
{ 
  pinMode(13, OUTPUT);
  nh.initNode();
  nh.subscribe(sub);
}

void loop()
{  
  nh.spinOnce();
  delay(1);
}
edit flag offensive delete link more

Comments

Hello Gary,

Thank you for your answer. Just one question, how do I print the x y theta values on the serial monitor? serial.print doesn't work.

rosdino gravatar image rosdino  ( 2015-08-06 03:49:25 -0500 )edit

You can't use serial.print directly since the serial port is already being used to communicate with the rosserial_python node.

You need to use the ROS' logger. There's an example under File->Examples->ros_lib->Logging in your Arduino IDE

Gary Servin gravatar image Gary Servin  ( 2015-08-06 07:58:27 -0500 )edit

Thanks :-)

rosdino gravatar image rosdino  ( 2015-08-06 09:19:18 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-08-03 21:34:03 -0500

Seen: 1,879 times

Last updated: Aug 04 '15