ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Running Can Radar on Ros through Raspberry Pi 2

asked 2015-07-13 12:37:23 -0500

williswalker94 gravatar image

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.1... cable and the PI Can board http://skpang.co.uk/catalog/pican-can... .

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_interfa... 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!

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
1

answered 2015-08-04 19:48:52 -0500

Mathias Lüdtke gravatar image

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;
}
edit flag offensive delete link more

Comments

Thanks for the suggestion.

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

Droter gravatar image Droter  ( 2015-09-23 20:40:17 -0500 )edit

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.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2015-09-24 14:19:39 -0500 )edit

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

Josh Whitley gravatar image Josh Whitley  ( 2017-09-08 14:42:29 -0500 )edit
0

answered 2015-07-13 21:59:46 -0500

ahendrix gravatar image

It sounds like you're going in the right direction; the Linux SocketCAN API is the right place to start.

I've had good luck working with the raw SocketCAN API in the past; I haven't played with the ROS socketcan_interface package. It looks like it's probably more complicated than you need, and there are no obvious code examples of how to use it.

You don't have to use the ROS socketcan_interface package; you can compile and link directly against the linux SocketCAN API if you want to.

You should probably stay away from the CANOpen packages, unless your radar uses the CANOpen protocol.

It also sounds like you aren't getting consistent results from you CAN interface; if you've had it working on both your laptop and the raspberry Pi, that means that the kernel drivers work. You should take careful notes about the interface setup process, and make sure that you can reliably run a simple tool like candump before you try to get a custom program to work. In particular, make sure that you have good notes and a good process for setting up the CAN interface after rebooting the machine.

edit flag offensive delete link more

Comments

socketcan_interface is completely independent from the CANopen packages. It does not even need/use ROS (apart from catkin and class_loader).

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2015-08-04 19:53:03 -0500 )edit

Hi Mathias,

I gave it a try and posted a question here: http://answers.ros.org/question/21819... it is close but not publishing the right data.

Droter gravatar image Droter  ( 2015-09-25 02:01:16 -0500 )edit

Question Tools

Stats

Asked: 2015-07-13 12:37:23 -0500

Seen: 2,189 times

Last updated: Aug 04 '15