Skip to content

MRASL/hokuyo-datareading-urg-node2

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

27 Commits
 
 
 
 
 
 
 
 

Repository files navigation

Hokuyo-Data-Reading

This document is mainly about how to retrieve data from the Hokuyo UST-20LX laser connected to the RPi 3, and visualize the cloud points on your own desktop or any device.

Prerequisites

  • OS: Ubuntu 20.04 LTS
  • ROS 2: Galactic
  • Create a ROS 2 workspace
  • Download the package: urg_node2
$ cd <ROS2_workspace>/src
$ git clone --recursive https://github.com/Hokuyo-aut/urg_node2.git

Raspberry Pi 3

After the RPi 3 is powered on, type the login information as following,

username: ubuntu
password: david1234
  1. Broadcast the laser's ethernet IP address to RPi 3
$ sudo ip addr add 192.168.0.15/24 broadcast 192.168.1.255 dev eth0
  1. Under Ros 2 worksapce, run rosdep to check for missing dependencies before building
$ rosdep install -i --from-path src --rosdistro galactic -y
  1. Build the package
$ colcon build --packages-select urg_node2
  1. Source the setup files
$ . install/setup.bash
  1. Launch the node to active state to scan the distribution of the cloud points
$ ros2 launch urg_node2 urg_node2.launch.py

Desktop

  1. Under ROS 2 workspace, build the package
$ colcon build --packages-select laserscan_subscriber
  1. Source the setup files
$ . install/setup.bash
  1. Activate the node and collect the data from RPi 3
$ ros2 run laserscan_subscriber laserscan_subscriber 
  1. Click the enter button, the lidar will scan once and save the data into the CSV file, including the position of objects in the body frame, the distance data, and the corresponding angle data.

Code explannation

The laserscan_subscriber.cpp was created for subscribing the data from the laser. We used the Eigen library to build the data structure. The data are saved as CSV file, the first col. is distance data, the second is angle data, the third and the fourth are calculated by the easy trigonometric function to put the (x,y) location. Function topic_callback specifys the way we adopt.

void topic_callback(const sensor_msgs::msg::LaserScan::SharedPtr msg) {
        cout<<"IN CALLBACK!!!"<<endl;
        //int anmin = 440;
        //int anmax = 640;
        int rm = 0; // to remove on each side of scan (0.25deg per measure)
        int anmin = rm;
        int anmax = 1080-rm;
        double div = 1.0; // multiply env for norm
        // reset data
        int j=0; // idx in data
        data.conservativeResize(j,NoChange);
        for (int i = anmin; i < anmax; i++) {
            dist[i] = msg->ranges[i];
            //if(dist[i]<=7 && dist[i]>=1){ // aritifcially limiting range
                data.conservativeResize(j+1,NoChange); // resize mat
                data(j,2) = dist[i]*div;  // set dist
                data(j,3) = theta(i);
                data(j,0) = data(j,2) * cos(theta(i)); // x
                data(j,1) = data(j,2) * sin(theta(i)); // y
                j++; // iterate
            //}
        }
        Scan scan;
        scan.data = data;
        scan.loc =  Vector2d({0, 0});
        scan.ori = 0;
        scan.write_scan(n++);
        cout << "*********************************************************" << endl;
        cin.get();
    }

About

No description, website, or topics provided.

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published