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

Axis direction using Rviz

asked 2021-03-16 15:14:55 -0500

mros gravatar image

updated 2021-03-18 11:12:54 -0500

Hello all, I am using the ROS Noetic and rviz to visualize lidar data. So, I am using tow frame:s the map frame , and a moving frame which is the lidar frame(led_short_frame) . I am using visualization_msgs::Marker PointsViz to visualize the lidar points. The problem is that I can't get the x axis for the point p.x and y axis for p.y data, i.e, it is reversed during visualization (the image below). The code is as follows:

#include <ros/ros.h>
#include <can_msgs/Frame.h>
#include <sensor_msgs/LaserScan.h>
#include <string>
#include <iostream>
#include <boost/array.hpp>
#include <boost/endian/conversion.hpp>
#include <leddar/leddar.h>
#include <leddar/leddar_xy.h>
#include <math.h>
#include <visualization_msgs/Marker.h>

 ros::Publisher chatter_pub;
ros::Publisher marker_pub;
bool data_ready_to_send = false;
int Count_nb_detections=0;
 #define PI 3.14159265
bool First_run=true;
int angle_segment[8]={69,75,81,87,93,99,105,111};
leddar::leddar_xy *leddar_xy_message_out;

void canFrameToXYCallback(const leddar::leddar::ConstPtr& msg_leddar)
{
     leddar_xy_message_out = new leddar::leddar_xy();
    visualization_msgs::Marker PointsViz;

    int new_nb_detections=0;
     float Cord_x=0.f,Cord_y =0.f;
     PointsViz.pose.orientation.w=1.0;
     PointsViz.header.frame_id="led_short_frame";
     PointsViz.header.stamp=ros::Time::now();
     PointsViz.color.g=1.0f;
     PointsViz.color.a=1.0f;
     PointsViz.scale.x=0.1;
     PointsViz.scale.y=0.1;
     PointsViz.pose.orientation.w=1.0;
     geometry_msgs::Point p;
     PointsViz.ns="points_and_lines";
     PointsViz.type=visualization_msgs::Marker::POINTS;
    for (unsigned int i =0 ;i< (msg_leddar->nb_detections);i++)

     {       


         if(msg_leddar->Distance[i]<60000)
    {
        if(msg_leddar->Flag[i]==1 || msg_leddar->Flag[i]==9 )
        {       new_nb_detections++;



                 leddar_xy_message_out->Distance.push_back(msg_leddar->Distance[i]);

                 leddar_xy_message_out->Flag.push_back(msg_leddar->Flag[i]);

                 leddar_xy_message_out->Magnitude.push_back(msg_leddar->Magnitude[i]);
                 leddar_xy_message_out->Segment.push_back(msg_leddar->Segment[i]);

                 Cord_x= 0.01f * msg_leddar->Distance[i] * cos(angle_segment[msg_leddar->Segment[i]]*PI/180)+0.082f ;
                 Cord_y= 0.01f * msg_leddar->Distance[i] * sin(angle_segment[msg_leddar->Segment[i]]*PI/180)+1.9f;

                 leddar_xy_message_out->Pos_x.push_back(Cord_x)  ;
                 leddar_xy_message_out->Pos_y.push_back(Cord_y)   ;
                p.x= Cord_x;
                p.y= Cord_y;
                 PointsViz.points.push_back(p);


        }

    }

     }

                leddar_xy_message_out -> nb_detections= new_nb_detections;




              if( new_nb_detections!=0)
              {
                marker_pub.publish(PointsViz);
                chatter_pub.publish(*leddar_xy_message_out);
               }    
}
int main(int argc, char *argv[])
{
  ros::init(argc, argv, "leddar_RawToXY_node");

  ros::NodeHandle n;

  chatter_pub = n.advertise<leddar::leddar_xy>("leddar_raw_to_XY", 100);
  marker_pub =  n.advertise<visualization_msgs::Marker> ("Marker_Viz_Leddar", 100);

  ros::Subscriber sub2 = n.subscribe("leddar_raw_data", 100, canFrameToXYCallback);

  ROS_INFO("receive_can_leddar_XY_48 ready - waiting for data ... ");

  ros::spin();

  return 0;
}

The tf is defined in the roslaunch file is:

<node pkg="tf" type="static_transform_publisher" name="transf_leddar_map" args="0 0 1 0 0 0 1 /map /led_short_frame 100" />

The FOV of the sensor is as following:

image description

Please, how I can get the same direction of the axis, between the point p and the used fame (p.x according to x axis and p.y according to y axis)?

image description Thank you

edit retag flag offensive close merge delete

Comments

Is led_long_frame your fixed frame in RViz?

tryan gravatar image tryan  ( 2021-03-16 20:01:50 -0500 )edit

no,it is a frame sensor and it moves

mros gravatar image mros  ( 2021-03-17 01:55:01 -0500 )edit

Ok, what is your fixed frame in RViz? Please, post the rest of your code for context.

tryan gravatar image tryan  ( 2021-03-17 08:11:08 -0500 )edit

Hello, it is the map frame. The problem is that when I plotted the geometry_msgs/Point.msg (p.x & p.y)), it is reversed during visualization and it does not respect the Lidar frame (arbitrary direction). Thank you.

mros gravatar image mros  ( 2021-03-17 08:42:00 -0500 )edit

I suspect you're plotting the point in the map frame rather than the lidar frame. Would that match the orientation of the map frame in the picture above? If not that, it may be some other frame-related mismatch.

tryan gravatar image tryan  ( 2021-03-17 09:00:53 -0500 )edit

I added the below figure for more details

mros gravatar image mros  ( 2021-03-17 13:35:05 -0500 )edit

Please, edit your question with new information rather than posting an answer. It's not clear to me how the second image relates to the first as none of the frames or points appear to be the same. Can you post your full code?

tryan gravatar image tryan  ( 2021-03-17 19:18:50 -0500 )edit
1

Ok, I edited the question and I updated it

mros gravatar image mros  ( 2021-03-18 04:45:17 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2021-03-18 12:09:50 -0500

tryan gravatar image

updated 2021-04-12 09:34:14 -0500

As mentioned in my comment, the convention is for angles to be measured counter-clockwise (right-hand rule) from the x axis (see REP 103). With a 48° field of view evenly split into 8 segments, each segment should be 6° as you noted. This user guide says the FoV is 47.5°, so you may want to double-check. I'll assume 48° here. If the FoV is centered on the x-axis (forward) in the lidar frame, the segment angles should be {21, 15, 9, 3, -3, -9, -15, -21} in degrees. Note that I'm assuming the segments are ordered left to right (segment 0 is left-most, the most positive angle), which agrees with the diagram on page 41 of the linked user guide, but that's another assumption that you should double-check. Here's a diagram for clarity:

image description


Update from @mros:

I checked the sensor and the segments are ordered right to left (not as mentioned in the datasheet). So, {-21,-15,-9,-3,3,9,15,21} is the order (from 0 to 7).

edit flag offensive delete link more

Comments

Hi Tryan, thank you so much for your help, but I think with the counter-clockwise direction, the positive values of angles will be in the right of the figure? no?

mros gravatar image mros  ( 2021-04-08 10:37:22 -0500 )edit

Please clarify if I'm misunderstanding you, but REP 103 (linked above) indicates that 0° is along the x-axis (forward) and angles increase counter-clockwise, following the right-hand rule, which would place positive angles to the left in the figure.

tryan gravatar image tryan  ( 2021-04-08 20:21:51 -0500 )edit
1

Hi, thank you again for your reply. Yes, 0° is along the x-axis (forward) and angles increase counter-clockwise. But, I checked the sensor and the segments are ordered right to left (not as mentioned in the datasheet). So, {-21,-15,-9,-3,3,9,15,21} is the order (from 0 to 7).

mros gravatar image mros  ( 2021-04-12 04:58:42 -0500 )edit
1

Ah, ok. The actual sensor is the most reliable source, so I'll take your word for it. In any case, does the 90° shift fix your issue?

tryan gravatar image tryan  ( 2021-04-12 08:40:33 -0500 )edit
1

Yes, it is ok, any shift works very well now, thank you.

mros gravatar image mros  ( 2021-04-12 09:23:55 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-03-16 15:14:55 -0500

Seen: 471 times

Last updated: Apr 12 '21