Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update to package names, launch files and topic names based on conventions #24

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 10 additions & 10 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -88,40 +88,40 @@ The scancontrol_driver_node connects to the scanCONTROL device and allows contro

#### Published Topics

* **`/scancontrol_pointcloud`** ([sensor_msgs/PointCloud2])
* **`profiles`** ([sensor_msgs/PointCloud2])

The laser scan data filtered by the partial profile settings. The last point(s) may get lost, as a timestamp overwrites the last 4 bytes of the measurement buffer.
The laser scan data filtered by the partial profile settings. The last point(s) may get lost, as a timestamp overwrites the last 4 bytes of the measurement buffer. Use the `frame_id` parameter to change the name of the reference frame in which the data is published.


#### Services
Most servives are wrappers of the scanCONTROL API. For more information on the available settings and values see the documentation as part of the [scanCONTROL Linux C++ SDK 0.2](https://www.micro-epsilon.com/2D_3D/laser-scanner/Software/downloads/). The rqt plugin uses these services to change the settings during runtime.

* **`~set_feature`** ([micro_epsilon_scancontrol_msgs/SetFeature])
* **`set_feature`** ([micro_epsilon_scancontrol_msgs/SetFeature])

Set a feature (setting) on the scanCONTROL device.


* **`~get_feature`** ([micro_epsilon_scancontrol_msgs/GetFeature])
* **`get_feature`** ([micro_epsilon_scancontrol_msgs/GetFeature])

Get the current feature (setting) from the connected scanCONTROL device.

* **`~get_resolution`** ([micro_epsilon_scancontrol_msgs/GetResolution])
* **`get_resolution`** ([micro_epsilon_scancontrol_msgs/GetResolution])

Get the current active resolution used by the connected scanCONTROL device.

* **`~set_resolution`** ([micro_epsilon_scancontrol_msgs/SetResolution])
* **`set_resolution`** ([micro_epsilon_scancontrol_msgs/SetResolution])

Set the resultion of the connected scanCONTROL device.

* **`~get_available_resolutions`** ([micro_epsilon_scancontrol_msgs/GetAvailableResolutions])
* **`get_available_resolutions`** ([micro_epsilon_scancontrol_msgs/GetAvailableResolutions])

Retrieve a list of all available resolutions of the connected scanCONTROL device.

* **`~invert_x`** ([std_srvs/SetBool])
* **`invert_x`** ([std_srvs/SetBool])

Flip the X values around the middle of the laser line of the sensor.

* **`~invert_z`** ([std_srvs/SetBool]
* **`invert_z`** ([std_srvs/SetBool]

Flip the Z values around the middle of the measuring range of the sensor. Factory default value of of this setting is `True`.

Expand All @@ -141,7 +141,7 @@ The following parameters are available to allow using multiple scanCONTROL devic

Define a custom name for the topic to publish the point cloud data on.

* **`frame_id`** (string, default: `scancontrol`)
* **`frame_id`** (string, default: `optical_frame`)

Define a custom name for the measurement frame in which the point clouds are published.

Expand Down

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@
#define MAX_RESOLUTION_COUNT 6
#define GENERAL_FUNCTION_FAILED -1

#define DEFAULT_FRAME_ID "scancontrol"
#define DEFAULT_TOPIC_NAME "scancontrol_pointcloud"
#define DEFAULT_FRAME_ID "optical_frame"
#define DEFAULT_TOPIC_NAME "profiles"

typedef pcl::PointCloud<pcl::PointXYZI> point_cloud_t;

Expand Down
13 changes: 7 additions & 6 deletions micro_epsilon_scancontrol_driver/launch/test_driver.launch
Original file line number Diff line number Diff line change
@@ -1,18 +1,19 @@
<launch>
<arg name="sensor_model" default="30x0" />

<!-- Load the Micro Epsilon scanCONTROL driver -->
<node name="scancontrol_driver" pkg="micro_epsilon_scancontrol_driver" type="driver_node" output="screen" required="true" />
<include ns="scancontrol" file="$(find micro_epsilon_scancontrol_driver)/launch/load_driver.launch"/>

<!-- Load the Micro Epsilon scanCONTROL description (URDF) -->
<include file="$(find micro_epsilon_scancontrol_description)/launch/load_scancontrol_26x0_29x0_25.launch" />
<include file="$(find micro_epsilon_scancontrol_support)/launch/load_26x0_29x0_25.launch" if="$(eval arg('sensor_model') == '26x0' or arg('sensor_model') == '29x0')"/>
<include file="$(find micro_epsilon_scancontrol_support)/launch/load_27x0_100.launch" if="$(eval arg('sensor_model') == '27x0')" />
<include file="$(find micro_epsilon_scancontrol_support)/launch/load_30x0_25.launch" if="$(eval arg('sensor_model') == '30x0')" />

<!-- Start the Joint State publisher and Robot State publisher (for correct visualization) -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="false" />
</node>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

<!-- Start Rviz to visualize the data -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find micro_epsilon_scancontrol_description)/config/rviz.rviz" required="true" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find micro_epsilon_scancontrol_support)/config/test_driver_config.rviz" required="true" />

</launch>
6 changes: 3 additions & 3 deletions micro_epsilon_scancontrol_driver/src/driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ namespace scancontrol_driver

// Check if the available device is the same as the prefered device (if a serial is provided):
std::string interface(available_interfaces[0]);
if ((config_.serial == "") || (interface.find(config_.serial) > -1)){
if ((config_.serial == "") || (interface.find(config_.serial) != std::string::npos)){
ROS_INFO_STREAM("Interface found: " << interface);
}
else{
Expand All @@ -78,7 +78,7 @@ namespace scancontrol_driver
if (config_.serial != ""){
for (int i = 0; i < interface_count; i++){
std::string interface(available_interfaces[i]);
if (interface.find(config_.serial) > -1){
if (interface.find(config_.serial) != std::string::npos){
ROS_INFO_STREAM("Interface found: " << interface);
selected_interface = i;
break;
Expand Down Expand Up @@ -163,7 +163,7 @@ namespace scancontrol_driver
gint8 selected_resolution = -1;
for (int i = 0; i < return_code; i++){
std::string resolution = std::to_string(available_resolutions[i]);
if (resolution.find(config_.serial) > -1){
if (resolution.find(config_.resolution) != std::string::npos){
selected_resolution = i;
break;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,15 @@
cmake_minimum_required(VERSION 2.8.3)

project(micro_epsilon_scancontrol_description)
project(micro_epsilon_scancontrol_support)

find_package(catkin REQUIRED)

catkin_package()

if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(tests/roslaunch_test.xml)
endif()

install(DIRECTORY config launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,9 @@ Panels:
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /TF1
- /TF1/Frames1
- /PointCloud21
Splitter Ratio: 0.5
Tree Height: 815
Tree Height: 796
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expand All @@ -18,7 +16,7 @@ Panels:
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Expand All @@ -29,6 +27,10 @@ Panels:
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
Expand All @@ -38,7 +40,7 @@ Visualization Manager:
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.03
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Expand Down Expand Up @@ -98,9 +100,9 @@ Visualization Manager:
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.01
Size (m): 0.009999999776482582
Style: Points
Topic: /profiles
Topic: /scancontrol/profiles
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Expand All @@ -109,9 +111,9 @@ Visualization Manager:
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: false
All Enabled: true
aperture_frame:
Value: false
Value: true
base_link:
Value: true
Marker Scale: 0.5
Expand All @@ -128,6 +130,7 @@ Visualization Manager:
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: base_link
Frame Rate: 30
Name: root
Expand All @@ -139,7 +142,10 @@ Visualization Manager:
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Expand All @@ -149,30 +155,33 @@ Visualization Manager:
Views:
Current:
Class: rviz/Orbit
Distance: 1.29337
Distance: 1.293370008468628
Enable Stereo Rendering:
Stereo Eye Separation: 0.06
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.01
Pitch: 0.785398
Near Clip Distance: 0.009999999776482582
Pitch: 0.6203983426094055
Target Frame: base_link
Value: Orbit (rviz)
Yaw: 0.785398
Yaw: 5.783589839935303
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1028
Height: 1025
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a000003befc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000003be000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003befc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000003be000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650000000000000004b0000002f600fffffffb0000000800540069006d006501000000000000045000000000000000000000013b000003be00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd00000004000000000000016a000003a7fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003a7000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003a7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003a7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650000000000000004b0000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004b8000003a700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
Expand All @@ -181,6 +190,6 @@ Window Geometry:
collapsed: false
Views:
collapsed: false
Width: 960
X: -10
Y: 14
Width: 1853
X: 67
Y: 27
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<launch>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find micro_epsilon_scancontrol_support)/urdf/26x0_29x0_25.xacro'" />
</launch>
3 changes: 3 additions & 0 deletions micro_epsilon_scancontrol_support/launch/load_27x0_100.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<launch>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find micro_epsilon_scancontrol_support)/urdf/27x0_100.xacro'" />
</launch>
3 changes: 3 additions & 0 deletions micro_epsilon_scancontrol_support/launch/load_30x0_25.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<launch>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find micro_epsilon_scancontrol_support)/urdf/30x0_25.xacro'" />
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<launch>
<include file="$(find micro_epsilon_scancontrol_support)/launch/load_26x0_29x0_25.launch" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find micro_epsilon_scancontrol_support)/config/rviz.rviz" required="true" />
</launch>
6 changes: 6 additions & 0 deletions micro_epsilon_scancontrol_support/launch/test_27x0_100.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<launch>
<include file="$(find micro_epsilon_scancontrol_support)/launch/load_27x0_100.launch" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find micro_epsilon_scancontrol_support)/config/rviz.rviz" required="true" />
</launch>
6 changes: 6 additions & 0 deletions micro_epsilon_scancontrol_support/launch/test_30x0_25.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<launch>
<include file="$(find micro_epsilon_scancontrol_support)/launch/load_30x0_25.launch" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find micro_epsilon_scancontrol_support)/config/rviz.rviz" required="true" />
</launch>
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<package>
<name>micro_epsilon_scancontrol_description</name>
<name>micro_epsilon_scancontrol_support</name>
<version>0.1.0</version>
<description>URDFs for the Micro-Epsilon scanCONTROL laser profile sensors.</description>
<maintainer email="[email protected]">Rik Tonnaer (Delft University of Technology)</maintainer>
Expand Down
Loading