OuyangJunyuan / TricycleWebots_Sim

A tricycle simulation in Webots
0 stars 0 forks source link

webots激光雷达在 RIVZ可视化Lidar的问题 #4

Open OuyangJunyuan opened 3 years ago

OuyangJunyuan commented 3 years ago

首先需要发布TF

/*CMakeLists.txt:

find_package(catkin REQUIRED COMPONENTS
....
  tf2
  tf2_ros
....
)
*/

/*cpp code:
    #include <geometry_msgs/TransformStamped.h>
    #include <tf2_ros/static_transform_broadcaster.h> 
    #include <tf2/LinearMath/Quaternion.h>

    geometry_msgs::TransformStamped static_transformStamped;
    static_transformStamped.header.stamp = ros::Time::now();
    static_transformStamped.header.frame_id = "world";
    static_transformStamped.child_frame_id = "TricycleSensor/Hokuyo_URG_04LX";
    static_transformStamped.transform.translation.x = 0;
    static_transformStamped.transform.translation.y = 0;
    static_transformStamped.transform.translation.z = 0;
    tf2::Quaternion quat;
    quat.setRPY(0,0,0);
    static_transformStamped.transform.rotation.x = quat.x();
    static_transformStamped.transform.rotation.y = quat.y();
    static_transformStamped.transform.rotation.z = quat.z();
    static_transformStamped.transform.rotation.w = quat.w();
    static_broadcaster.sendTransform(static_transformStamped);
*/
OuyangJunyuan commented 3 years ago

然后代码中从ros里通过webots_ros 发布的services中申请使能雷达

/*cpp code
#include <webots_ros/set_bool.h>
#include <webots_ros/set_int.h>
   //使能lidarscan信息发布
    set_lidar_client = n.serviceClient<webots_ros::set_int>("/TricycleSensor/Hokuyo_URG_04LX/enable");
    lidar_srv.request.value = timeStep;
    while (!(set_lidar_client.call(lidar_srv) && lidar_srv.response.success));、

   //使能点云信息发布
   set_lidar_pc_client=n.serviceClient<webots_ros::set_bool("/TricycleSensor/Hokuyo_URG_04LX/enable_point_cloud");
   lidar_pc_srv.request.value = true;
    while (!(set_lidar_pc_client.call(lidar_pc_srv) && lidar_pc_srv.response.success));
*/
OuyangJunyuan commented 3 years ago

然后在rviz中,把fixed frame选择world。 添加话题数据,选择对应激光雷达的话题。 如果报错,可能是激光雷达信息中指定的雷达frame 没有被发布指定,需要在上面tf2的发布中指定child_frame_id为本lidar的frameid。就可以了。