Skip to content

Commit 357abfd

Browse files
committed
Added additional log and updated default configs
1 parent d71daa4 commit 357abfd

File tree

3 files changed

+5
-3
lines changed

3 files changed

+5
-3
lines changed

libwaterlinked/src/client.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -242,7 +242,7 @@ auto WaterLinkedClient::get_configuration() -> std::future<CommandResponse>
242242

243243
auto WaterLinkedClient::set_configuration(const Configuration & configuration) -> std::future<CommandResponse>
244244
{
245-
nlohmann::json config_json = configuration;
245+
const nlohmann::json config_json = configuration;
246246
return send_command({{"command", "set_config"}, {"parameters", config_json}});
247247
}
248248

waterlinked_dvl_driver/src/waterlinked_dvl_driver.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -280,6 +280,8 @@ auto WaterLinkedDvlDriver::on_configure(const rclcpp_lifecycle::State & /*previo
280280
populate_service_response(response, f);
281281
});
282282

283+
RCLCPP_INFO(get_logger(), "WaterLinkedDvlDriver loaded successfully");
284+
283285
return CallbackReturn::SUCCESS;
284286
}
285287

waterlinked_dvl_driver/src/waterlinked_dvl_driver_parameters.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,15 +25,15 @@ waterlinked_dvl_driver:
2525

2626
speed_of_sound:
2727
type: int
28-
default_value: 1500
28+
default_value: 1481
2929
description: "The speed of sound in water (m/s)."
3030
read_only: true
3131
validation:
3232
bounds<>: [1000, 2000]
3333

3434
mounting_rotation_offset:
3535
type: int
36-
default_value: 0
36+
default_value: 180
3737
description: "The mounting rotation offset of the DVL (degrees)."
3838
read_only: true
3939
validation:

0 commit comments

Comments
 (0)