From 961f0ff58f0964b775dabab39018914bb9778caa Mon Sep 17 00:00:00 2001 From: Ken Robinson Date: Sun, 4 Jun 2023 22:46:35 +1000 Subject: [PATCH 1/2] Update raptor_dbw_can_node.cpp Using type infomration to upgrade to humble ros --- raptor_dbw_can/src/raptor_dbw_can_node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/raptor_dbw_can/src/raptor_dbw_can_node.cpp b/raptor_dbw_can/src/raptor_dbw_can_node.cpp index f8cfb14..f7b2b39 100644 --- a/raptor_dbw_can/src/raptor_dbw_can_node.cpp +++ b/raptor_dbw_can/src/raptor_dbw_can_node.cpp @@ -39,9 +39,9 @@ int main(int argc, char ** argv) // Get parameter values auto temp = std::make_shared("get_dbw_params_node", options); - temp->declare_parameter("dbw_dbc_file"); - temp->declare_parameter("max_steer_angle"); - + temp->declare_parameter("dbw_dbc_file", rclcpp::PARAMETER_STRING); + temp->declare_parameter("max_steer_angle", rclcpp::PARAMETER_DOUBLE); + std::string n_dbw_dbc_file = temp->get_parameter("dbw_dbc_file").as_string(); float n_max_steer_angle = temp->get_parameter("max_steer_angle").as_double(); From 1afd4715fc9160834497122373da4e79270b9f6a Mon Sep 17 00:00:00 2001 From: Ken Robinson Date: Mon, 5 Jun 2023 12:57:57 +0000 Subject: [PATCH 2/2] Upgraded to humble --- raptor_dbw_joystick/src/raptor_dbw_joystick_node.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/raptor_dbw_joystick/src/raptor_dbw_joystick_node.cpp b/raptor_dbw_joystick/src/raptor_dbw_joystick_node.cpp index ac6db8e..1b3e8db 100644 --- a/raptor_dbw_joystick/src/raptor_dbw_joystick_node.cpp +++ b/raptor_dbw_joystick/src/raptor_dbw_joystick_node.cpp @@ -39,10 +39,10 @@ int main(int argc, char ** argv) // Get parameter values auto temp = std::make_shared("get_joy_params_node", options); - temp->declare_parameter("ignore"); - temp->declare_parameter("enable"); - temp->declare_parameter("svel"); - temp->declare_parameter("max_steer_angle"); + temp->declare_parameter("ignore", rclcpp::PARAMETER_BOOL); + temp->declare_parameter("enable", rclcpp::PARAMETER_BOOL); + temp->declare_parameter("svel", rclcpp::PARAMETER_DOUBLE); + temp->declare_parameter("max_steer_angle", rclcpp::PARAMETER_DOUBLE); bool n_ignore = temp->get_parameter("ignore").as_bool(); bool n_enable = temp->get_parameter("enable").as_bool();