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

motor pwm config via param and dynparam #36

Open
wants to merge 2 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
51 changes: 42 additions & 9 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,34 +1,61 @@
cmake_minimum_required(VERSION 2.8.3)
project(rplidar_ros)

find_package(catkin REQUIRED COMPONENTS
roscpp
rosconsole
sensor_msgs
dynamic_reconfigure
)

################################################
## Declare ROS messages, services and actions ##
################################################

################################################
## Declare ROS dynamic reconfigure parameters ##
################################################

generate_dynamic_reconfigure_options(
cfg/Lidar.cfg
)

###################################
## catkin specific configuration ##
###################################

catkin_package(
)

###########
## Build ##
###########

set(RPLIDAR_SDK_PATH "./sdk/")

FILE(GLOB RPLIDAR_SDK_SRC
file(GLOB RPLIDAR_SDK_SRC
"${RPLIDAR_SDK_PATH}/src/arch/linux/*.cpp"
"${RPLIDAR_SDK_PATH}/src/hal/*.cpp"
"${RPLIDAR_SDK_PATH}/src/*.cpp"
)

find_package(catkin REQUIRED COMPONENTS
roscpp
rosconsole
sensor_msgs
)

include_directories(
${RPLIDAR_SDK_PATH}/include
${RPLIDAR_SDK_PATH}/src
${catkin_INCLUDE_DIRS}
)

catkin_package()

add_executable(rplidarNode src/node.cpp ${RPLIDAR_SDK_SRC})
target_link_libraries(rplidarNode ${catkin_LIBRARIES})
add_dependencies(rplidarNode ${catkin_EXPORTED_TARGETS})

add_executable(rplidarNodeClient src/client.cpp)
target_link_libraries(rplidarNodeClient ${catkin_LIBRARIES})

#############
## Install ##
#############

install(TARGETS rplidarNode rplidarNodeClient
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand All @@ -39,3 +66,9 @@ install(DIRECTORY launch rviz sdk
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
)

#############
## Testing ##
#############

# vim: set ft=cmake et fenc=utf-8 ff=unix sts=0 sw=2 ts=2 :
10 changes: 10 additions & 0 deletions cfg/Lidar.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#!/usr/bin/env python
PACKAGE = "rplidar_ros"

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

gen.add("motor_pwm", int_t, 0, "The motor pwm", 660, 200, 1000)

exit(gen.generate(PACKAGE, "rplidar_ros", "Lidar"))
31 changes: 26 additions & 5 deletions launch/rplidar.launch
Original file line number Diff line number Diff line change
@@ -1,9 +1,30 @@
<launch>
<arg name="serial_port" default="/dev/ttyUSB0"/>
<arg name="serial_baudrate" default="115200"/>
<arg name="frame_id" default="laser"/>
<arg name="inverted" default="false"/>
<arg name="angle_compensate" default="true"/>
<arg name="motor_pwm" default="660"/>
<arg name="rviz" default="false"/>
<arg name="test" default="false"/>

<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB0"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
<param name="serial_port" type="string" value="$(arg serial_port)"/>
<param name="serial_baudrate" type="int" value="$(arg serial_baudrate)"/>
<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="inverted" type="bool" value="$(arg inverted)"/>
<param name="angle_compensate" type="bool" value="$(arg angle_compensate)"/>
<param name="motor_pwm" type="int" value="$(arg motor_pwm)"/>
</node>

<group if="$(arg rviz)">
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find rplidar_ros)/rviz/rplidar.rviz"/>
</group>

<group if="$(arg test)">
<node name="rplidarNodeClient" pkg="rplidar_ros" type="rplidarNodeClient" output="screen"/>
</group>

</launch>

<!-- vim: set et fenc=utf-8 ff=unix sts=0 sw=2 ts=2 : -->
12 changes: 0 additions & 12 deletions launch/test_rplidar.launch

This file was deleted.

10 changes: 0 additions & 10 deletions launch/view_rplidar.launch

This file was deleted.

2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,11 @@
<build_depend>rosconsole</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_srvs</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>rosconsole</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>dynamic_reconfigure</run_depend>

</package>
2 changes: 1 addition & 1 deletion src/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ int main(int argc, char **argv)
ros::init(argc, argv, "rplidar_node_client");
ros::NodeHandle n;

ros::Subscriber sub = n.subscribe<sensor_msgs::LaserScan>("/scan", 1000, scanCallback);
ros::Subscriber sub = n.subscribe<sensor_msgs::LaserScan>("/rplidarNode/scan", 1000, scanCallback);

ros::spin();

Expand Down
Loading