Skip to content

Commit

Permalink
v0.2.0
Browse files Browse the repository at this point in the history
  • Loading branch information
cygbot committed Feb 23, 2022
1 parent b8ae165 commit b30e990
Show file tree
Hide file tree
Showing 6 changed files with 30 additions and 11 deletions.
9 changes: 4 additions & 5 deletions launch/cyglidar.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<launch>
<!-- Arguments -->
<arg name="version" default="2" doc="version type [0, 1, 2]"/>
<arg name="version" default="2" doc="version type [0, 1, 2]"/> <!-- 0: 2D, 1: 3D, 2: Dual -->
<arg name="frequency_level" default="0" doc="level [0 to 15]"/>
<arg name="pulse_control" default="0" doc="pulse mode [0, 1]"/> <!-- 0: Auto, 1: Manual -->
<arg name="pulse_duration" default="10000" doc="duration [0 to 10000]"/>
Expand All @@ -10,13 +10,12 @@
<param name="baud_rate" value="3000000"/>
<param name="frame_id" value="laser_link"/>
<param name="fixed_frame" value="/map"/>

<param name="version" value="$(arg version)"/>
<param name="run_mode" value="$(arg version)"/>
<param name="frequency" value="$(arg frequency_level)"/>
<param name="pulse_control" value="$(arg pulse_control)"/>
<param name="set_auto_duration" value="$(arg pulse_control)"/>
<param name="duration" value="$(arg pulse_duration)"/>
</node>

<node pkg="rviz" type="rviz" name="rviz" args="-d $(find cyglidar_d1)/rviz/cyglidar_config.rviz"/>
<node pkg="tf" type="static_transform_publisher" name="to_laserlink" args="0 0 0 0 0 0 1 map laser_link 10"/>
</launch>
</launch>
Binary file modified screenshots/param_2d.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file modified screenshots/param_2d3d.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file modified screenshots/param_3d.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Empty file modified scripts/create_udev_rules.sh
100644 → 100755
Empty file.
32 changes: 26 additions & 6 deletions src/cyglidar_pcl_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
#include "PointCloudMaker.h"
#include "Constants_CygLiDAR_D1.h"

int RunMode; // select run mode {2D(0), 3D(1), Dual(2)}
int setAutoDuration; // select Auto (1) or Fixed(0)
int DATABUFFER_SIZE_2D, DATABUFFER_SIZE_3D, DATASET_SIZE_2D, DATASET_SIZE_3D;

typedef pcl::PointCloud<pcl::PointXYZRGBA> PointXYZRGBA;
Expand Down Expand Up @@ -233,7 +235,7 @@ void cloudScatter_3D()
}
}

int VERSION_NUM, FREQUENCY_LEVEL, PULSE_CONTROL, PULSE_DURATION;
int FREQUENCY_LEVEL, PULSE_DURATION;
void running()
{
// Create node handlers and local variables
Expand All @@ -249,15 +251,33 @@ void running()
priv_nh.param("baud_rate", baud_rate, 3000000);
priv_nh.param("frame_id", frame_id, std::string("laser_link"));

priv_nh.param("version", VERSION_NUM, 0);
priv_nh.param("run_mode", RunMode, 0);
priv_nh.param("frequency", FREQUENCY_LEVEL, 0);
priv_nh.param("pulse_control", PULSE_CONTROL, 0);
priv_nh.param("set_auto_duration", setAutoDuration, 0);
priv_nh.param("duration", PULSE_DURATION, 0);

// injection run mode
eRunMode LiDAR_RunMode;
switch(RunMode)
{
case 0:
LiDAR_RunMode = eRunMode::Mode2D;
break;
case 1:
LiDAR_RunMode = eRunMode::Mode3D;
break;
case 2:
LiDAR_RunMode = eRunMode::ModeDual;
break;
default:
LiDAR_RunMode = eRunMode::Mode3D;
break;
}

// Check whether the values are applied properly
ROS_INFO("FREQUENCY: %d (%x) / PULSE CONTROL: %d, DURATION: %d (%x)", \
FREQUENCY_LEVEL, FREQUENCY_LEVEL, \
PULSE_CONTROL, PULSE_DURATION, PULSE_DURATION);
setAutoDuration, PULSE_DURATION, PULSE_DURATION);

// Call the following function so as to store colors to draw 3D data
colorBuffer();
Expand Down Expand Up @@ -309,11 +329,11 @@ void running()
cyglidar_pcl laser(port, baud_rate, io);

// Send packets
laser.packet_run(eRunMode::ModeDual);
laser.packet_run(LiDAR_RunMode);
ros::Duration(1.0).sleep(); // sleep for a sec, by the duration
laser.packet_frequency(FREQUENCY_LEVEL);
ros::Duration(1.0).sleep();
laser.packet_duration(eRunMode::Mode3D, PULSE_CONTROL, PULSE_DURATION);
laser.packet_duration(LiDAR_RunMode, setAutoDuration, PULSE_DURATION);

// Create variables used to organize data before drawing
int DATA_1 = 4, DATA_2 = 3;
Expand Down

0 comments on commit b30e990

Please sign in to comment.