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

Publish radar ros message repeated detected objects.

asked 2021-06-20 17:19:16 -0500

sgttrieu gravatar image

updated 2021-06-21 09:45:09 -0500

Hi, I have a radar sensor to detect vehicles in front of the car. each detected object has its data in the form of

struct
{
   int32 ObjectID;
   float32 distance;
   float32 velocity;
   float32 zimuth ;
   float32 elevation;
} Radar_Point

I want to push this radar data using a standard ROS message I found the message

radar_msgs/msg/RadarScan.msg

std_msgs/Header header
radar_msgs/RadarReturn[] returns

and

radar_msgs/msg/RadarReturn.msg

# All variables below are relative to the radar's frame of reference.
# This message is not meant to be used alone but as part of a stamped or array message.

float32 range                            # Distance (m) from the sensor to the detected return.
float32 azimuth                          # Angle (in radians) in the azimuth plane between the sensor and the detected return.
                                         #    Positive angles are anticlockwise from the sensor and negative angles clockwise from the sensor as per REP-0103.
float32 elevation                        # Angle (in radians) in the elevation plane between the sensor and the detected return.
                                         #    Negative angles are below the sensor. For 2D radar, this will be 0.
float32 doppler_velocity                 # The doppler speeds (m/s) of the return.
float32 amplitude                        # The amplitude of the of the return (dB)

I find it difficult to map the radar sensor data to the radar ros message before I can publish it.

radar_msgs::RadarScan msgRadarScan;

ros::init(argc, argv, "conti_radar"); ros::NodeHandle n; ros::Publisher publisher_contiradar = n.advertise <radar_msgs::radarscan>("/conti_radar", 100);

void handledata( const double & simTime, const unsigned int & simFrame, std::vector<Radar_Point> & item, bool isExtended )
{
    for (auto i = item.begin(); i != item.end(); ++i)
    {
        msgRadarScan.header.stamp.sec = simTime;
        msgRadarScan.header.stamp.nsec = (simTime - msgRadarScan.header.stamp.sec)*1000000000;
        msgRadarScan.header.frame_id = "base_link";
        msgRadarScan.returns.range =  item[i].distance;
        msgRadarScan.returns.velocity =  item[i].doppler_velocity;
        msgRadarScan.returns.zimuth =  item[i].azimuth;
        msgRadarScan.returns.elevation =  item[i].elevation;
        msgRadarScan.returns.push_back();
    }
}

publisher_contiradar.publish(msgRadarScan);

I try to implement in this way because For the radar sensor data, I have a number of detected objects. So I am thinking about adding a newly detected object to an array or vector?. Certainly, my code is wrong with many errors I just want to give you an idea about my idea. Can anyone help me to review the message conversion part? there must be a better way to publish Radar data to the ROS server. Please give me some suggestion

edit retag flag offensive close merge delete

Comments

I try to assign ROS message parameters with the radar sensor but there are many errors?

I don't believe anyone can help you, unless you clarify what "many errors" actually means.

gvdhoorn gravatar image gvdhoorn  ( 2021-06-21 04:45:21 -0500 )edit

Hi gvdhoorn I will specify more details about the errors. Thanks for pointing it out.

sgttrieu gravatar image sgttrieu  ( 2021-06-21 06:21:05 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-06-20 22:14:41 -0500

Do you specifically need the RadarMsg? Why not create a custom message for your needs? You can follow the official tutorial from ROS.

In your case you can define myRadarScan.msg

Header header
int32
float32 distance
float32 velocity
float32 zimuth
float32 elevation
edit flag offensive delete link more

Comments

Yes, I do understand the custom message and it is not my problem. For example, if publish GPS sensor it is very simple. I can directly assign values of GPS custom message and publish. However, GPS is just data from a single object (an ego vehicle). Radar or Lidar sensors are different. Sensor data are from different detected objects. Each detected object has its own values, we need to create a loop or something to publish the data. Range and distance are just the names. I have no problem with that. The problem is to publish data from different detected objects. I hope you understand what I mean otherwise I will try to explain it clearer.

sgttrieu gravatar image sgttrieu  ( 2021-06-21 01:56:32 -0500 )edit

Do you specifically need the RadarMsg? Why not create a custom message for your needs?

it's actually really valuable to use a standardised message. If only for the benefit of being able to reuse standardised tooling, instead of having to write everything yourself.

@sgttrieu: +100 for trying to use radar_msgs.

gvdhoorn gravatar image gvdhoorn  ( 2021-06-21 04:44:47 -0500 )edit

Hi Gvdhoorn, Could you please give the link to the standard radar message radar_msgs? I could not find the radar message in the sensor_msgs package. I thought the one I use is the standard radar message. You can find the messages which I use below https://github.com/ros-perception/rad...

sgttrieu gravatar image sgttrieu  ( 2021-06-21 06:30:48 -0500 )edit

@sgttrieu: that is the standard message. It's just not in common_msgs.

gvdhoorn gravatar image gvdhoorn  ( 2021-06-21 07:45:33 -0500 )edit

ok, please correct me if I am wrong. common_msgs includes actionlid_msgs, diagnostic_msgs, geometry_msgs, nav_msgs and sensor_msgs so radar_msgs is not available in common_msgs. Does it mean I have to create the radar_msgs using the combination of other message packages in common_msgs?

sgttrieu gravatar image sgttrieu  ( 2021-06-21 09:13:33 -0500 )edit

I understand the value in using standard msgs. Using a custom msg was just an option since you said that you were encountering errors. Could you share the errors you are receiving? or maybe a screenshot of what you get vs what you expect?

Akhil Kurup gravatar image Akhil Kurup  ( 2021-06-21 09:14:47 -0500 )edit

Hi Akhil Kurup, I would say, forgetting about correcting errors. What I want to know more about is a method to publish continuously detected objects to ROS. I feel the way I implement is not the right way so firstly I need someone to review my method and suggest me the right way to do it.

sgttrieu gravatar image sgttrieu  ( 2021-06-21 09:44:15 -0500 )edit

This kind of a question is hard to answer. What I am might find as the 'right way' might not be what you want. I'd suggest you define what you want and see if your code does that. If not, what are you getting and what can be done about it

Akhil Kurup gravatar image Akhil Kurup  ( 2021-06-21 11:22:48 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-06-20 17:19:16 -0500

Seen: 318 times

Last updated: Jun 21 '21