Skip to content

Commit

Permalink
Merge pull request #14 from krobinson/humble
Browse files Browse the repository at this point in the history
Humble update
  • Loading branch information
JWhitleyWork authored Dec 18, 2024
2 parents 38ec131 + 1afd471 commit 07afd10
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
6 changes: 3 additions & 3 deletions raptor_dbw_can/src/raptor_dbw_can_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,9 @@ int main(int argc, char ** argv)

// Get parameter values
auto temp = std::make_shared<rclcpp::Node>("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();

Expand Down
8 changes: 4 additions & 4 deletions raptor_dbw_joystick/src/raptor_dbw_joystick_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@ int main(int argc, char ** argv)

// Get parameter values
auto temp = std::make_shared<rclcpp::Node>("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();
Expand Down

0 comments on commit 07afd10

Please sign in to comment.