1
2

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

More than 1 year has passed since last update.

北陽電機製2D-LiDAR(UTM-LX-30)をROSで動かす方法ー2

Posted at

はじめに

Ubuntu 18.04 LTS
ROS melodic
https://qiita.com/yacht0425/items/594ba89deddca9b18e34
でurg_nodeはインストール済み

https://qiita.com/yacht0425/items/41e54a0e5eade05b7479
でROSのワークスペースは構築済み

1.ソースコードを追加する

urg_node_test.cppという名前のソースコードを追加した

~/ros_ws/src/urg_node_test.cpp
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/LaserScan.h>

void cbScan(const sensor_msgs::LaserScan::ConstPtr &msg)
{
  int i = msg->ranges.size() / 2;
  if (msg->ranges[i] < msg->range_min || // エラー値の場合
      msg->ranges[i] > msg->range_max || // 測定範囲外の場合
      std::isnan(msg->ranges[i])) // 無限遠の場合
  {
    ROS_INFO("front-range: measurement error");
  }
  else
  {
    ROS_INFO("front-range: %0.3f",
      msg->ranges[msg->ranges.size() / 2]);
  }
}

int main(int argc, char** argv) {

  ros::init(argc, argv, "urg_test_node");
  ros::NodeHandle nh;

  ros::Subscriber sub_scan_ = nh.subscribe("scan", 5, cbScan);

  ros::spin();

  return 0;
}

2.CmakeLists.txtも忘れずに編集

以下の2つを追加

~/ros_ws/CmakeLists.txt
add_executable(urg_test_node src/urg_test_node.cpp)

target_link_libraries(urg_test_node
  ${catkin_LIBRARIES}
)

3.ターミナルを開き以下を実行

terminal 1
rosrun
terminal 2
rosrun urg_node urg_node _serial_port:=/dev/ttyACM0
terminal 3
rosrun rosrun utm_lx_30 urg_test_node

urg_nodeはシリアルに権限を与えるのを忘れないこと

参考文献

1
2
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
1
2

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?