Skip to content

Commit d571560

Browse files
authored
updates for 24.04/Jazzy/Harmonic (#67)
* fixes for 24.04/jazzy/harmonic Signed-off-by: Michael Anderson <anderson@mbari.org> * fix CI for 24.04/jazzy/harmonic Signed-off-by: Michael Anderson <anderson@mbari.org> * updates for 24.04/jazzy/harmonic Signed-off-by: Michael Anderson <anderson@mbari.org> * in python buoy api, use callback groups instead of asyncio to handle clients and subs Signed-off-by: Michael Anderson <anderson@mbari.org> * update interface to add inc wave height service and latent data callbacks; clean up back end ros2 callback handling Signed-off-by: Michael Anderson <anderson@mbari.org> * fix pbcmd to use new spin in interface Signed-off-by: Michael Anderson <anderson@mbari.org> * update api documentation Signed-off-by: Michael Anderson <anderson@mbari.org> * linters Signed-off-by: Michael Anderson <anderson@mbari.org> --------- Signed-off-by: Michael Anderson <anderson@mbari.org>
1 parent ceec8dc commit d571560

File tree

13 files changed

+1209
-260
lines changed

13 files changed

+1209
-260
lines changed

.github/workflows/ci.yml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,13 +9,13 @@ on:
99
jobs:
1010
tests:
1111
name: Build and test
12-
runs-on: ubuntu-22.04
12+
runs-on: ubuntu-24.04
1313
strategy:
1414
matrix:
1515
include:
16-
- ros-distro: "humble"
16+
- ros-distro: "jazzy"
1717
container:
18-
image: ubuntu:22.04
18+
image: ubuntu:24.04
1919
steps:
2020
- name: Checkout
2121
uses: actions/checkout@v2

buoy_api_cpp/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
cmake_minimum_required(VERSION 3.8)
1+
cmake_minimum_required(VERSION 3.28)
22
project(buoy_api_cpp)
33

44
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")

buoy_api_cpp/examples/include/buoy_api/examples/torque_controller.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@
1818
#include <memory>
1919
#include <string>
2020

21+
#include <buoy_interfaces/msg/pc_record.hpp> // power
22+
2123
#include <buoy_api/interface.hpp>
2224

2325
// forward declare

buoy_api_cpp/examples/torque_controller.cpp

Lines changed: 33 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@
1818
#include <string>
1919
#include <memory>
2020

21+
#include <buoy_interfaces/srv/inc_wave_height.hpp>
22+
2123

2224
PBTorqueController::PBTorqueController(const std::string & node_name)
2325
: buoy_api::Interface<PBTorqueController>(node_name)
@@ -30,30 +32,51 @@ PBTorqueController::PBTorqueController(const std::string & node_name)
3032

3133
void PBTorqueController::power_callback(const buoy_interfaces::msg::PCRecord & data)
3234
{
33-
auto request = std::make_shared<buoy_interfaces::srv::PCWindCurrCommand::Request>();
34-
request->wind_curr = policy_->WindingCurrentTarget(data.rpm, data.scale, data.retract);
35+
float wind_curr = policy_->WindingCurrentTarget(data.rpm, data.scale, data.retract);
3536

3637
RCLCPP_INFO_STREAM(
3738
rclcpp::get_logger(
3839
this->get_name()),
3940
"WindingCurrent: f(" << data.rpm << ", " << data.scale << ", " << data.retract << ") = " <<
40-
request->wind_curr);
41+
wind_curr
42+
);
4143

42-
PCWindCurrServiceCallback pc_wind_curr_callback =
43-
default_service_response_callback<PCWindCurrServiceCallback,
44-
PCWindCurrServiceResponseFuture>();
44+
auto future = this->send_pc_wind_curr_command(wind_curr);
4545

46-
// NOTE: Move semantics destroys local
47-
// pc_wind_curr_callback object
48-
auto response = pc_wind_curr_client_->async_send_request(request, pc_wind_curr_callback);
46+
/*
47+
// Example using the full API
48+
auto future = this->send_pc_wind_curr_command(
49+
wind_curr, // command value
50+
true, // blocking
51+
0.1, // timeout in seconds
52+
true // use default callback
53+
);
54+
if (future.valid())
55+
{
56+
RCLCPP_INFO_STREAM(
57+
rclcpp::get_logger(
58+
this->get_name()),
59+
"Got valid pc wind curr command response: " << static_cast<int>(future.get()->result.value)
60+
);
61+
}
62+
else
63+
{
64+
RCLCPP_ERROR(
65+
rclcpp::get_logger(
66+
this->get_name()),
67+
"pc wind curr command did not complete within timeout"
68+
);
69+
}
70+
*/
4971
}
5072

5173

5274
int main(int argc, char ** argv)
5375
{
5476
rclcpp::init(argc, argv);
5577

56-
rclcpp::spin(std::make_shared<PBTorqueController>("pb_torque_controller"));
78+
auto controller = std::make_shared<PBTorqueController>("pb_torque_controller");
79+
controller->spin();
5780
rclcpp::shutdown();
5881

5982
return 0;

0 commit comments

Comments
 (0)