run:
colcon build
- source install/setup.bash && ros2 run pioneer3DX_controller Pioneer3DX_Controller
+ source install/setup.bash && ros2 run pioneer3dx_controller Pioneer3dx_Controller
debug:
colcon build --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
- source install/setup.bash && ros2 run --prefix 'gdb -ex start --args' pioneer3DX_controller Pioneer3DX_Controller
+ source install/setup.bash && ros2 run --prefix 'gdb -ex start --args' pioneer3dx_controller Pioneer3dx_Controller
cmake_minimum_required(VERSION 3.8)
-project(pioneer3DX_controller)
+project(pioneer3dx_controller)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(nav_msgs REQUIRED)
+find_package(service_msgs REQUIRED)
+find_package(rosidl_default_generators REQUIRED)
-add_executable(Pioneer3DX_Controller src/main.cpp src/p3dx_node.cpp)
-ament_target_dependencies(Pioneer3DX_Controller rclcpp nav_msgs)
-install(TARGETS Pioneer3DX_Controller DESTINATION lib/${PROJECT_NAME})
+rosidl_generate_interfaces(${PROJECT_NAME}
+ "messages/ChangeMode.msg"
+ "messages/ConfigLed.msg"
+ "messages/ConfigPid.msg"
+ "messages/ConfigRobot.msg"
+ "services/ChangeMode.srv"
+ "services/ConfigLed.srv"
+ "services/ConfigPid.srv"
+ "services/ConfigRobot.srv"
+ DEPENDENCIES service_msgs
+)
+
+add_executable(Pioneer3dx_Controller src/main.cpp src/p3dx_node.cpp)
+ament_target_dependencies(Pioneer3dx_Controller rclcpp nav_msgs)
+rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
+target_link_libraries(Pioneer3dx_Controller ${cpp_typesupport_target})
+install(TARGETS Pioneer3dx_Controller DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
--- /dev/null
+byte mode
\ No newline at end of file
--- /dev/null
+float32 voltage_red
+float32 voltage_orange
+float32 voltage_hysteresis
+uint32 update_period
\ No newline at end of file
--- /dev/null
+float32[3] left
+float32[3] right
+float32[3] cross
\ No newline at end of file
--- /dev/null
+float32 baseline
+float32 wheel_circumference_left
+float32 wheel_circumference_right
+uint32 ticks_per_revolution_left
+uint32 ticks_per_revolution_right
\ No newline at end of file
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
- <name>pioneer3DX_controller</name>
+ <name>pioneer3dx_controller</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="leo@todo.todo">leo</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
+ <buildtool_depend>rosidl_default_generators</buildtool_depend>
<depend>rclcpp</depend>
+ <depend>nav_msgs</depend>
+ <depend>service_msgs</depend>
+
+ <exec_depend>rosidl_default_runtime</exec_depend>
+
+ <member_of_group>rosidl_interface_packages</member_of_group>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
--- /dev/null
+byte mode
+---
+byte status_response
\ No newline at end of file
--- /dev/null
+float32 voltage_red
+float32 voltage_orange
+float32 voltage_hysteresis
+uint32 update_period
+---
+byte status_response
--- /dev/null
+float32[3] left
+float32[3] right
+float32[3] cross
+---
+byte status_response
\ No newline at end of file
--- /dev/null
+float32 baseline
+float32 wheel_circumference_left
+float32 wheel_circumference_right
+uint32 ticks_per_revolution_left
+uint32 ticks_per_revolution_right
+---
+byte status_response
\ No newline at end of file
#include "p3dx_node.hpp"
+#include "pioneer3dx_controller/msg/change_mode.hpp"
+
using namespace std::chrono_literals;
P3DX_Controller_Node::P3DX_Controller_Node() :
"\n header.crc = %u",
message_types[msg->header.type], msg->header.crc);
assert(buffer_len > 0);
- assert(buffer_len < sizeof(buffer));
+ assert(buffer_len < (int32_t)sizeof(buffer));
switch (msg->header.type) {
case FMW_MessageType_Response: {
"\n ticks_right = %d",
result_types[msg->response.result], msg->response.delta_millis,
msg->response.ticks_left, msg->response.ticks_right);
- assert(buffer_len < sizeof(buffer));
+ assert(buffer_len < (int32_t)sizeof(buffer));
} break;
default: {
assert(false && "unreachable");