How does the ROS-side host machine interface identify a rosserial-enabled device
SBC: Rpi 4B/4GB OS: Ubuntu 20.04 ROS: Noetic
Background: I presently have a robot chassis that is running ROS Noetic on an Rpi 4B/4GB and has multiple USB inputs from various detectors and controllers. I have an Arduino Uno R3 that is monitoring two IR receivers and is using rosserial to send IR Receiver beam detection data as irCode.x = flag2; and irCode.x = flag3; via ros::Publisher pub("irCode", &irCode); to the ROS-side host machine (Rpi 4B).
Question: How does the ROS-side host machine interface identify the correct USB port that the Arduino Uno R3 is attached to in the host machine ROS node code? The ROS-side host machine code does not appear to have any ROS commands that identify the Arduino USB port number and baud speed (57600). I have looked at the rosserial_python example and that example uses 'serial_node.py' to interface to a rosserial-enabled device, but I do not see an equivalent ROS function in the host machine node code to detect the Arduino (rosserial-endabled device).
#include <ros/ros.h>
#include <geometry_msgs/Vector3.h>
#include <geometry_msgs/Twist.h>
ros::Publisher cmd_vel_pub;
ros::Subscriber irValue_sub;
unsigned int foundDockingStation = 0;
geometry_msgs::Vector3 vec3;
void irValueCallback(const geometry_msgs::Vector3 &vector3)
{
//omega_left = vector3.x;
//omega_right = vector3.y;
vec3.x = vector3.x;
vec3.y = vector3.y;
if (foundDockingStation) {
geometry_msgs::TwistPtr cmd(new geometry_msgs::Twist());
cmd->linear.x = -0.08;
cmd->angular.z = 0.1 * (vector3.x - vector3.y);
if (vector3.x || vector3.y)
cmd_vel_pub.publish(cmd);
}
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "mybot_autodocking_irCode");
ros::NodeHandle nh;
cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 50);
irValue_sub = nh.subscribe("/irCode", 10, irValueCallback);
vec3.x = 0; //initiallized with some big values
vec3.y = 0;
ros::Rate r(10);
while (ros::ok())
{
ros::spinOnce();
printf("x=%f, y=%f\n", vec3.x, vec3.y);
if (!foundDockingStation && vec3.x == 0.0 && vec3.y == 0.0) {
geometry_msgs::TwistPtr cmd(new geometry_msgs::Twist());
cmd->angular.z = 0.1; // const rotate until
cmd->linear.x = 0.0;
cmd_vel_pub.publish(cmd);
} else {
foundDockingStation = 1;
}
r.sleep();
}
return 0;
}
Comments?
Regards, TCIII
What do you mean by:
what should be "detected" exactly?
rosserial
allows an embedded device to "speak ROS". It doesn't matter for other ROS nodes where ROS nodes "are", what they are or what they do. The only things that matter are publishers, subscribers, services, actions and parameters. Therosserial
server implements a proxy, which takes care of receiving and transmitting data from and to your embedded device. That proxy is the ROS node, not your Arduino. The proxy needs the device file name and baudrate. None of the other ROS nodes need it, as they're not "talking" to an Arduino on/dev/ttyUSB0
at57600
baud, but to therosserial
server, over ROS topics.If you could clarify what you mean by "detect[ing]" and "identify[ing ...(more)