0
$\begingroup$

Rosanswers logo

I need to send radar data to a bagfile on the raspberry pi 2.

I have access to the peak-USB http://www.peak-system.com/PCAN-USB.199.0.html?&L=1 cable and the PI Can board http://skpang.co.uk/catalog/pican-canbus-board-for-raspberry-pi-p-1196.html.

I can output a log file on the raspberry pi 2 outside of ros using the candump command after downloading can-utils.

I can also get the Peak-USB cord to work with my laptop but not the raspberry pi 2 in ros after installing cancom, can_msgs, and cob_extern from github.com.

I have looked into http://wiki.ros.org/socketcan_interface?distro=indigo but have struggled to get that to work on either my laptop of the raspberry pi 2.

I am new to ROS and looking for the easiest and not necessary the best method to achieve this goal. Thanks!


Originally posted by williswalker94 on ROS Answers with karma: 1 on 2015-07-13

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

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;
}

Originally posted by Mathias Lüdtke with karma: 1596 on 2015-08-04

This answer was ACCEPTED on the original site

Post score: 1


Original comments

Comment by Droter on 2015-09-23:
Thanks for the suggestion.

How do you publish the can data to a ROS topic?

Comment by Mathias Lüdtke on 2015-09-24:
This code snippet does not publish ROS messages! See http://wiki.ros.org/ROS/Tutorials and other answers for help on writing a publisher. There is no (standard) ROS message type for CAN data, so you have to write your own. Or even better: use common message types for the decoded data.

Comment by Josh Whitley on 2017-09-08:
Actually, there is a standardized type for CAN messages but it may have only been made official after this question was answered. See http://wiki.ros.org/can_msgs

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.