Skip to content

Commit 15435ab

Browse files
destogllivanov93
andauthored
Fixing foxy CI (#157)
* Fixing foxy CI Co-authored-by: livanov93 <[email protected]>
1 parent 4c89b1b commit 15435ab

File tree

3 files changed

+6
-7
lines changed

3 files changed

+6
-7
lines changed

.github/workflows/ci-build-binary-foxy.yml renamed to .github/workflows/ci-build-binary.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
name: Binary Build - Foxy
1+
name: Binary Build
22
on:
33
pull_request:
44
branches:

ur_controllers/src/force_torque_sensor_broadcaster.cpp

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -32,11 +32,10 @@ controller_interface::return_type ForceTorqueStateBroadcaster::init(const std::s
3232
}
3333

3434
try {
35-
auto node = get_node();
36-
node->declare_parameter<std::vector<std::string>>("state_interface_names", {});
37-
node->declare_parameter<std::string>("sensor_name", "");
38-
node->declare_parameter<std::string>("topic_name", "");
39-
node->declare_parameter<std::string>("frame_id", "");
35+
auto_declare<std::vector<std::string>>("state_interface_names", {});
36+
auto_declare<std::string>("sensor_name", "");
37+
auto_declare<std::string>("topic_name", "");
38+
auto_declare<std::string>("frame_id", "");
4039
} catch (const std::exception& e) {
4140
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
4241
return controller_interface::return_type::ERROR;

ur_controllers/src/speed_scaling_state_broadcaster.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ controller_interface::InterfaceConfiguration SpeedScalingStateBroadcaster::state
6060
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
6161
SpeedScalingStateBroadcaster::on_configure(const rclcpp_lifecycle::State& /*previous_state*/)
6262
{
63-
node_->declare_parameter("state_publish_rate");
63+
auto_declare<double>("state_publish_rate", 100.0);
6464

6565
if (!node_->get_parameter("state_publish_rate", publish_rate_)) {
6666
RCLCPP_INFO(get_node()->get_logger(), "Parameter 'state_publish_rate' not set");

0 commit comments

Comments
 (0)