Hi Lukasz,
They do have the same message definitions.
On one CORE2-ROS my custom Feedback message is working, on this CORE2-ROS I generated the Feedback message headers after making the message here. Then I copied the message header file to the CORE2 of both devies. Exactly the same code and message does not work on the other CORE2-ROS and gives me this error:
[ERROR] [1558684707.038321]: Creation of publisher failed: 'module' object has no attribute 'Feedback'
The other error comes from the subscriber to the ArmControl message:
[ERROR] [1558619511.146625]: Creation of subscriber failed: ARVI_GUI
ROS path [0]=/opt/ros/kinetic/share/ros
ROS path [1]=/home/husarion/ros-workspace/src
ROS path [2]=/opt/ros/kinetic/share
main.cpp:
#include "hFramework.h"
#include "hCloudClient.h"
#include "ros.h"
#include "messages/Feedback.h"
#include "messages/ArmControl.h"
#include <stdio.h>
using namespace hFramework;
ros::NodeHandle nh;
arvi_base::Feedback feedback;
ros::Publisher *feedback_pub;
int publish_counter = 0;
/* --- ARM CONTROL --- */
void armControlCallback(const ARVI_GUI::ArmControl &msg) {
// feedback.Component.data = "arm control";
// feedback.Message.data = "set arm position has been called";
// feedback.Success.data = 1;
// feedback_pub->publish(&feedback);
}
void initArmControlSubscriber() {
ros::Subscriber<ARVI_GUI::ArmControl> *arm_control_sub = new ros::Subscriber<ARVI_GUI::ArmControl>("/ArmControl", &armControlCallback);
nh.subscribe(*arm_control_sub);
}
/* --- FEEDBACK --- */
/* Initializes the feedback publisher */
void initFeedbackPublisher() {
feedback.header.frame_id = "base";
feedback_pub = new ros::Publisher("feedback", &feedback);
nh.advertise(*feedback_pub);
}
void hMain() {
/* Initializes communication with the Raspberry Pi */
RPi.init(500000);
platform.begin(&RPi);
nh.getHardware()->initWithDevice(&platform.LocalSerial);
nh.initNode();
uint32_t t = sys.getRefTime();
sys.setLogDev(&Serial);
/* INIT SUBSCRIBERS */
initArmControlSubscriber();
/* INIT PUBLISHERS */
initFeedbackPublisher();
/* CREATE TASKS */
while(true) {
nh.spinOnce();
publish_counter++;
if (publish_counter > 10) {
/* Execute simple code here, but rather in their specific tasks */
LED1.toggle();
publish_counter = 0;
}
sys.delaySync(t, 10);
}
}
Feedback.h
#ifndef _ROS_arvi_base_Feedback_h
#define _ROS_arvi_base_Feedback_h
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include "ros/msg.h"
#include "std_msgs/Header.h"
#include "std_msgs/String.h"
#include "std_msgs/UInt8.h"
namespace arvi_base
{
class Feedback : public ros::Msg
{
public:
typedef std_msgs::Header _header_type;
_header_type header;
typedef std_msgs::String _Component_type;
_Component_type Component;
typedef std_msgs::String _Message_type;
_Message_type Message;
typedef std_msgs::UInt8 _Success_type;
_Success_type Success;
Feedback():
header(),
Component(),
Message(),
Success()
{
}
virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
offset += this->header.serialize(outbuffer + offset);
offset += this->Component.serialize(outbuffer + offset);
offset += this->Message.serialize(outbuffer + offset);
offset += this->Success.serialize(outbuffer + offset);
return offset;
}
virtual int deserialize(unsigned char *inbuffer)
{
int offset = 0;
offset += this->header.deserialize(inbuffer + offset);
offset += this->Component.deserialize(inbuffer + offset);
offset += this->Message.deserialize(inbuffer + offset);
offset += this->Success.deserialize(inbuffer + offset);
return offset;
}
const char * getType(){ return "arvi_base/Feedback"; };
const char * getMD5(){ return "e380bb0a220e95f4ec0d2cec55170ee9"; };
};
}
#endif
ArmControl.h
#ifndef _ROS_ARVI_GUI_ArmControl_h
#define _ROS_ARVI_GUI_ArmControl_h
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include "ros/msg.h"
#include "std_msgs/Int32.h"
#include "std_msgs/Float32.h"
namespace ARVI_GUI
{
class ArmControl : public ros::Msg
{
public:
typedef std_msgs::Int32 _X_position_type;
_X_position_type X_position;
typedef std_msgs::Int32 _Y_position_type;
_Y_position_type Y_position;
typedef std_msgs::Int32 _Z_position_type;
_Z_position_type Z_position;
typedef std_msgs::Float32 _Angle_type;
_Angle_type Angle;
ArmControl():
X_position(),
Y_position(),
Z_position(),
Angle()
{
}
virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
offset += this->X_position.serialize(outbuffer + offset);
offset += this->Y_position.serialize(outbuffer + offset);
offset += this->Z_position.serialize(outbuffer + offset);
offset += this->Angle.serialize(outbuffer + offset);
return offset;
}
virtual int deserialize(unsigned char *inbuffer)
{
int offset = 0;
offset += this->X_position.deserialize(inbuffer + offset);
offset += this->Y_position.deserialize(inbuffer + offset);
offset += this->Z_position.deserialize(inbuffer + offset);
offset += this->Angle.deserialize(inbuffer + offset);
return offset;
}
const char * getType(){ return "ARVI_GUI/ArmControl"; };
const char * getMD5(){ return "21875091cd743a3e0a5640ed1bcec1b7"; };
};
}
#endif