This example publishes and subscribes JointState messages for each connected CiA 402 device as well as uint8 messages for each connected digital IO device (CiA 401).
#include "bridge.h"
#include "logger.h"
#include "joint_state_publisher.h"
#include "joint_state_subscriber.h"
#include "entry_publisher.h"
#include "entry_subscriber.h"
#include <thread>
#include <chrono>
#include <memory>
int main(int argc, char* argv[]) {
const std::string busname = "slcan0";
const std::string baudrate = "500K";
PRINT("This example publishes and subscribes JointState messages for each connected CiA 402 device as well as"
<<"uint8 messages for each connected digital IO device (CiA 401).");
const double loop_rate = 10;
if (!master.
start(busname, baudrate)) {
ERROR("Starting master failed.");
return EXIT_FAILURE;
}
std::this_thread::sleep_for(std::chrono::seconds(1));
size_t num_devices_required = 1;
ERROR(
"Number of devices found: " << master.
num_devices() <<
". Waiting for " << num_devices_required <<
".");
PRINT("Trying to discover more nodes via NMT Node Guarding...");
std::this_thread::sleep_for(std::chrono::seconds(1));
}
ros::init(argc, argv, "canopen_bridge");
bool found = false;
PRINT(
"Found CiA "<<std::dec<<(
unsigned)profile<<
" device with node ID "<<device.
get_node_id()<<
": "<<device.
get_entry(
"manufacturer_device_name"));
if (profile==401) {
found = true;
device.
set_entry(
"Write output 8-bit/Digital Outputs 1-8", (uint8_t) 0xFF);
auto iopub = std::make_shared<kaco::EntryPublisher>(device, "Read input 8-bit/Digital Inputs 9-16");
auto iosub = std::make_shared<kaco::EntrySubscriber>(device, "Write output 8-bit/Digital Outputs 1-8");
} else if (profile==402) {
found = true;
PRINT("Set position mode");
PRINT("Enable operation");
device.
execute(
"enable_operation");
auto jspub = std::make_shared<kaco::JointStatePublisher>(device, 0, 350000);
auto jssub = std::make_shared<kaco::JointStateSubscriber>(device, 0, 350000);
}
}
if (!found) {
ERROR("This example is intended for use with a CiA 402 device but I can't find one.");
return EXIT_FAILURE;
}
}