This example shows how to use the ROS bridge which in this case subscribes and publishes topics to get and set digital input/output of a CiA 401 device. It requires that you have plugged in a CiA 401 device with 16 digital outputs and 8 digital inputs.
#include "bridge.h"
#include "logger.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";
if (!master.
start(busname, baudrate)) {
ERROR("Starting master failed.");
return EXIT_FAILURE;
}
std::this_thread::sleep_for(std::chrono::seconds(1));
ERROR("No devices found.");
return EXIT_FAILURE;
}
if (profile != 401) {
ERROR("This example is intended for use with a CiA 401 device. You plugged a device with profile number "<<std::dec<<profile);
return EXIT_FAILURE;
}
DUMP(device.
get_entry(
"Manufacturer device name"));
device.
set_entry(
"Write output 8-bit/Digital Outputs 1-8", (uint8_t) 0xFF);
ros::init(argc, argv, "canopen_bridge");
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");
}