ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
socketcan_interface
is released for PCs and even armhf platforms, so it might run on the raspberry pi 2 out of the (ROS) box. If candump can0
works then rosrun socketcan_interface socketcan_dump can0
should work as well.
It works asynchronously, if that does not suit your purpose, you should work with raw socketcan as @ahendrix suggested.
A simple program (without error handling) with socketcan_interface:
#include <socketcan_interface/socketcan.h>
#include <socketcan_interface/threading.h>
#include <socketcan_interface/string.h>
void handleFrames(const can::Frame &f){
// handle all frames
LOG("got: " << can::tostring(f, true)); // lowercase: true
}
void handleFrame123(const can::Frame &f){
// handle specific frame
LOG("123? " << can::tostring(f, true)); // lowercase: true
}
int main(){
can::ThreadedSocketCANInterface driver;
if(!driver.init("can0", false)) return 1; // read own messages: false
can::CommInterface::FrameListener::Ptr all_frames = driver.createMsgListener(handleFrames);
can::CommInterface::FrameListener::Ptr one_frame = driver.createMsgListener(can::MsgHeader(0x123), handleFrame123); // handle only frames with CAN-ID 0x123
for(int i=0; i <10; ++i){ // send 10 messages, one per second
driver.send(can::toframe("042#23")); // cansend syntax
boost::this_thread::sleep_for(boost::chrono::seconds(1));
}
driver.shutdown();
return 0;
}