Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(ars548): updated the driver according to new documentation #253

Merged
merged 21 commits into from
Feb 18, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
21 commits
Select commit Hold shift + click to select a range
a22a695
feat: updated the ars548 driver according to new received documentation
knzo25 Jan 20, 2025
9424af1
chore: removed logs and added the max time slot value
knzo25 Jan 21, 2025
daeb43c
chore: added the min/maz frequencies as constants
knzo25 Jan 21, 2025
1ecd4d2
chore: fixed compilation errors
knzo25 Jan 21, 2025
681efb3
chore: added units to a print
knzo25 Feb 10, 2025
5909afc
chore: replaced hardcoded strings for some defined in the message
knzo25 Feb 10, 2025
114ac93
chore: removed hardcoded numbers in print
knzo25 Feb 10, 2025
b10082b
chore: refactored the rate checker logic into a class
knzo25 Feb 10, 2025
ff00898
chore: replaced hardcoded prints
knzo25 Feb 10, 2025
79a01d4
chore: refactored the ring buffer
knzo25 Feb 10, 2025
52162e9
Merge branch 'main' into feat/ars548_update
knzo25 Feb 10, 2025
65872f7
chore: refactored for clarity
knzo25 Feb 12, 2025
fc4cefb
chore: added the units to the variable names
knzo25 Feb 12, 2025
0d2efb5
chore: replaced ifelse clauses byt switch
knzo25 Feb 12, 2025
a34cb38
Revert "chore: replaced ifelse clauses byt switch"
knzo25 Feb 12, 2025
c15aaa0
chore: deleted duplicated logic with method call
knzo25 Feb 12, 2025
17aabf7
chore: deleted unused code
knzo25 Feb 12, 2025
8dc4b8d
chore: replaced initial check with the use of an optional
knzo25 Feb 12, 2025
d7fe448
fix: fixed burst of messages sent to the radar during startup
knzo25 Feb 12, 2025
9ea0c67
Merge branch 'feat/ars548_update' of github.com:knzo25/nebula into fe…
knzo25 Feb 12, 2025
bec4751
Merge branch 'main' into feat/ars548_update
knzo25 Feb 13, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -253,10 +253,19 @@ constexpr int sync_lost = 3;
constexpr int plug_right = 0;
constexpr int plug_left = 1;

constexpr int maximum_distance_min_value = 93;
constexpr int maximum_distance_max_value = 1514;

constexpr int frequency_slot_low = 0;
constexpr int frequency_slot_mid = 1;
constexpr int frequency_slot_high = 2;

constexpr int min_cycle_time_ms = 50;
constexpr int max_cycle_time_ms = 100;

constexpr int min_time_slot_ms = 10;
constexpr int max_time_slot_ms = 90;

constexpr int hcc_worldwide = 1;
constexpr int hcc_japan = 2;

Expand All @@ -280,6 +289,9 @@ constexpr int blockage_test_failed = 0;
constexpr int blockage_test_passed = 1;
constexpr int blockage_test_ongoing = 2;

constexpr int min_odometry_hz = 10;
constexpr int max_odometry_hz = 50;

#pragma pack(push, 1)

struct HeaderPacket
Expand Down
56 changes: 56 additions & 0 deletions nebula_common/include/nebula_common/util/rate_checker.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
// Copyright 2025 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include "nebula_common/util/ring_buffer.hpp"

namespace nebula::util
{

class RateChecker

Check warning on line 22 in nebula_common/include/nebula_common/util/rate_checker.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/rate_checker.hpp#L22

Added line #L22 was not covered by tests
{
public:
RateChecker(double min_rate_hz, double max_rate_hz, std::size_t buffer_size)
: min_rate_hz_(min_rate_hz), max_rate_hz_(max_rate_hz), ring_buffer_(buffer_size)

Check warning on line 26 in nebula_common/include/nebula_common/util/rate_checker.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/rate_checker.hpp#L26

Added line #L26 was not covered by tests
{
}

bool is_full() const { return ring_buffer_.is_full(); }

void update(double stamp)
{
if (last_stamp_) {
ring_buffer_.push_back(stamp - last_stamp_.value());

Check warning on line 35 in nebula_common/include/nebula_common/util/rate_checker.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/rate_checker.hpp#L35

Added line #L35 was not covered by tests
}

last_stamp_ = stamp;

Check warning on line 38 in nebula_common/include/nebula_common/util/rate_checker.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/rate_checker.hpp#L38

Added line #L38 was not covered by tests
}

bool is_valid() const
{
double average = get_average();
return average >= min_rate_hz_ && average <= max_rate_hz_;

Check warning on line 44 in nebula_common/include/nebula_common/util/rate_checker.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/rate_checker.hpp#L44

Added line #L44 was not covered by tests
}

double get_average() const { return 1.0 / ring_buffer_.get_average(); }

Check warning on line 47 in nebula_common/include/nebula_common/util/rate_checker.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/rate_checker.hpp#L47

Added line #L47 was not covered by tests

private:
std::optional<double> last_stamp_;
double min_rate_hz_;
double max_rate_hz_;
RingBuffer<double> ring_buffer_;
};

} // namespace nebula::util
55 changes: 55 additions & 0 deletions nebula_common/include/nebula_common/util/ring_buffer.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
// Copyright 2025 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include <algorithm>
#include <stdexcept>
#include <vector>

namespace nebula::util
{

template <typename T>
class RingBuffer
{
public:
explicit RingBuffer(std::size_t capacity) { buffer_.reserve(capacity); }

Check warning on line 28 in nebula_common/include/nebula_common/util/ring_buffer.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/ring_buffer.hpp#L28

Added line #L28 was not covered by tests

void push_back(const T & value)

Check warning on line 30 in nebula_common/include/nebula_common/util/ring_buffer.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/ring_buffer.hpp#L30

Added line #L30 was not covered by tests
{
if (is_full()) {
sum_ -= buffer_[index_];
buffer_[index_] = value;

Check warning on line 34 in nebula_common/include/nebula_common/util/ring_buffer.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/ring_buffer.hpp#L33-L34

Added lines #L33 - L34 were not covered by tests
} else {
buffer_.push_back(value);

Check warning on line 36 in nebula_common/include/nebula_common/util/ring_buffer.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/ring_buffer.hpp#L36

Added line #L36 was not covered by tests
}

sum_ += value;
index_ = (index_ + 1) % buffer_.capacity();

Check warning on line 40 in nebula_common/include/nebula_common/util/ring_buffer.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/ring_buffer.hpp#L39-L40

Added lines #L39 - L40 were not covered by tests
}

std::size_t size() const { return buffer_.size(); }

bool is_full() const { return buffer_.size() == buffer_.capacity(); }

T get_average() const { return sum_ / buffer_.size(); }

Check warning on line 47 in nebula_common/include/nebula_common/util/ring_buffer.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/util/ring_buffer.hpp#L47

Added line #L47 was not covered by tests

private:
T sum_{};
std::vector<T> buffer_;
std::size_t index_{0};
};

} // namespace nebula::util
Original file line number Diff line number Diff line change
Expand Up @@ -486,7 +486,7 @@
radar_status_.hcc = "1:Worldwide";
break;
case hcc_japan:
radar_status_.hcc = "1:Japan";
radar_status_.hcc = "2:Japan";

Check warning on line 489 in nebula_decoders/src/nebula_decoders_continental/decoders/continental_ars548_decoder.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_decoders/src/nebula_decoders_continental/decoders/continental_ars548_decoder.cpp#L489

Added line #L489 was not covered by tests
break;
default:
radar_status_.hcc = std::to_string(sensor_status_packet.status.hcc) + ":Invalid hcc";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -191,14 +191,25 @@
}

Status ContinentalARS548HwInterface::set_radar_parameters(
uint16_t maximum_distance, uint8_t frequency_slot, uint8_t cycle_time, uint8_t time_slot,
uint16_t maximum_distance, uint8_t frequency_slot, uint8_t cycle_time_ms, uint8_t time_slot_ms,
uint8_t hcc, uint8_t power_save_standstill)
{
if (
maximum_distance < 93 || maximum_distance > 1514 || frequency_slot > 2 || cycle_time < 50 ||
cycle_time > 100 || time_slot < 10 || time_slot > 90 || hcc < 1 || hcc > 2 ||
power_save_standstill > 1) {
print_error("Invalid SetRadarParameters values");
maximum_distance < maximum_distance_min_value ||

Check warning on line 198 in nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp#L198

Added line #L198 was not covered by tests
maximum_distance > maximum_distance_max_value) {
print_error("Invalid maximum_distance value");
return Status::SENSOR_CONFIG_ERROR;

Check warning on line 201 in nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp#L200-L201

Added lines #L200 - L201 were not covered by tests
}

if (cycle_time_ms < min_cycle_time_ms || cycle_time_ms > max_cycle_time_ms) {
print_error("Invalid cycle_time_ms value");
return Status::SENSOR_CONFIG_ERROR;

Check warning on line 206 in nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp#L205-L206

Added lines #L205 - L206 were not covered by tests
}

if (
time_slot_ms < min_time_slot_ms || time_slot_ms > cycle_time_ms - 1 ||

Check warning on line 210 in nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp#L209-L210

Added lines #L209 - L210 were not covered by tests
time_slot_ms > max_time_slot_ms) {
print_error("Invalid time_slot_ms value");

Check warning on line 212 in nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp#L212

Added line #L212 was not covered by tests
return Status::SENSOR_CONFIG_ERROR;
}

Expand All @@ -209,8 +220,8 @@
configuration_packet.header.length = configuration_payload_length;
configuration_packet.configuration.maximum_distance = maximum_distance;
configuration_packet.configuration.frequency_slot = frequency_slot;
configuration_packet.configuration.cycle_time = cycle_time;
configuration_packet.configuration.time_slot = time_slot;
configuration_packet.configuration.cycle_time = cycle_time_ms;
configuration_packet.configuration.time_slot = time_slot_ms;

Check warning on line 224 in nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp#L223-L224

Added lines #L223 - L224 were not covered by tests
configuration_packet.configuration.hcc = hcc;
configuration_packet.configuration.powersave_standstill = power_save_standstill;
configuration_packet.new_radar_parameters = 1;
Expand All @@ -219,9 +230,9 @@
std::memcpy(send_vector.data(), &configuration_packet, sizeof(ConfigurationPacket));

print_info("maximum_distance = " + std::to_string(maximum_distance));
print_info("frequency_slot = " + std::to_string(frequency_slot));
print_info("cycle_time = " + std::to_string(cycle_time));
print_info("time_slot = " + std::to_string(time_slot));
print_info("frequency_slot = " + std::to_string(frequency_slot) + " ms");
print_info("cycle_time = " + std::to_string(cycle_time_ms) + " ms");
print_info("time_slot = " + std::to_string(time_slot_ms) + " ms");

Check warning on line 235 in nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp#L233-L235

Added lines #L233 - L235 were not covered by tests
print_info("hcc = " + std::to_string(hcc));
print_info("power_save_standstill = " + std::to_string(power_save_standstill));

Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,13 @@
string FREQUENCY_BAND_LOW="low"
string FREQUENCY_BAND_MID="mid"
string FREQUENCY_BAND_HIGH="high"
string COUNTRY_CODE_JAPAN="japan"
string COUNTRY_CODE_WORLDWIDE="worldwide"
uint16 maximum_distance
uint16 frequency_slot
uint16 cycle_time
uint16 time_slot
uint16 country_code
string frequency_band
uint16 cycle_time_ms
uint16 time_slot_ms
string country_code
uint16 powersave_standstill
---
bool success
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include "nebula_ros/common/parameter_descriptors.hpp"

#include <nebula_common/continental/continental_ars548.hpp>
#include <nebula_common/util/rate_checker.hpp>
#include <nebula_hw_interfaces/nebula_hw_interfaces_continental/continental_ars548_hw_interface.hpp>
#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -114,6 +115,10 @@ class ContinentalARS548HwInterfaceWrapper
acceleration_sub_{};
rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr steering_angle_sub_{};

nebula::util::RateChecker odometry_rate_checker_;
nebula::util::RateChecker acceleration_rate_checker_;
nebula::util::RateChecker steering_angle_rate_checker_;

bool standstill_{true};

rclcpp::Service<continental_srvs::srv::ContinentalArs548SetNetworkConfiguration>::SharedPtr
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,16 @@
std::make_shared<nebula::drivers::continental_ars548::ContinentalARS548HwInterface>()),
logger_(parent_node->get_logger().get_child("HwInterfaceWrapper")),
status_(Status::NOT_INITIALIZED),
config_ptr_(config_ptr)
config_ptr_(config_ptr),
odometry_rate_checker_(
nebula::drivers::continental_ars548::min_odometry_hz,
nebula::drivers::continental_ars548::max_odometry_hz, 100),
acceleration_rate_checker_(
nebula::drivers::continental_ars548::min_odometry_hz,
nebula::drivers::continental_ars548::max_odometry_hz, 100),
steering_angle_rate_checker_(
nebula::drivers::continental_ars548::min_odometry_hz,
nebula::drivers::continental_ars548::max_odometry_hz, 100)

Check warning on line 45 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L45

Added line #L45 was not covered by tests
{
hw_interface_->set_logger(
std::make_shared<rclcpp::Logger>(parent_node->get_logger().get_child("HwInterface")));
Expand Down Expand Up @@ -125,6 +134,24 @@
void ContinentalARS548HwInterfaceWrapper::odometry_callback(
const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg)
{
using nebula::drivers::continental_ars548::max_odometry_hz;
using nebula::drivers::continental_ars548::min_odometry_hz;

double stamp = msg->header.stamp.sec + msg->header.stamp.nanosec * 1e-9;

Check warning on line 140 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L140

Added line #L140 was not covered by tests
odometry_rate_checker_.update(stamp);

if (!odometry_rate_checker_.is_full()) {
return;
} else if (!odometry_rate_checker_.is_valid()) {
double estimated_hz = odometry_rate_checker_.get_average();
rclcpp::Clock clock{RCL_ROS_TIME};
RCLCPP_WARN_THROTTLE(

Check warning on line 148 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L147-L148

Added lines #L147 - L148 were not covered by tests
logger_, clock, 5000,
"The current odometry rate is %.2f Hz. The sensor requires a rate in the range of %dHz to "
"%dHz",
estimated_hz, min_odometry_hz, max_odometry_hz);
}

Check warning on line 153 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L153

Added line #L153 was not covered by tests

constexpr float speed_to_standstill = 0.5f;
constexpr float speed_to_moving = 2.f;

Expand All @@ -150,13 +177,51 @@
void ContinentalARS548HwInterfaceWrapper::acceleration_callback(
const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg)
{
using nebula::drivers::continental_ars548::max_odometry_hz;
using nebula::drivers::continental_ars548::min_odometry_hz;

double stamp = msg->header.stamp.sec + msg->header.stamp.nanosec * 1e-9;

Check warning on line 183 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L183

Added line #L183 was not covered by tests
acceleration_rate_checker_.update(stamp);

if (!acceleration_rate_checker_.is_full()) {
return;
} else if (!acceleration_rate_checker_.is_valid()) {
double estimated_hz = acceleration_rate_checker_.get_average();
rclcpp::Clock clock{RCL_ROS_TIME};
RCLCPP_WARN_THROTTLE(

Check warning on line 191 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L190-L191

Added lines #L190 - L191 were not covered by tests
logger_, clock, 5000,
"Current acceleration rate is %.2f Hz. The sensor requires a rate in the range of %dHz to "
"%dHz",
estimated_hz, min_odometry_hz, max_odometry_hz);
}

Check warning on line 196 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L196

Added line #L196 was not covered by tests

hw_interface_->set_acceleration_lateral_cog(msg->accel.accel.linear.y);
hw_interface_->set_acceleration_longitudinal_cog(msg->accel.accel.linear.x);
}

void ContinentalARS548HwInterfaceWrapper::steering_angle_callback(
const std_msgs::msg::Float32::SharedPtr msg)
{
using nebula::drivers::continental_ars548::max_odometry_hz;
using nebula::drivers::continental_ars548::min_odometry_hz;

const auto now = std::chrono::high_resolution_clock::now();

Check warning on line 208 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L208

Added line #L208 was not covered by tests
const double stamp =
1e-9 * std::chrono::duration_cast<std::chrono::nanoseconds>(now.time_since_epoch()).count();

Check warning on line 210 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L210

Added line #L210 was not covered by tests
steering_angle_rate_checker_.update(stamp);

if (!steering_angle_rate_checker_.is_full()) {
return;

Check warning on line 214 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L214

Added line #L214 was not covered by tests
} else if (!steering_angle_rate_checker_.is_valid()) {
double estimated_hz = steering_angle_rate_checker_.get_average();
rclcpp::Clock clock{RCL_ROS_TIME};
RCLCPP_WARN_THROTTLE(

Check warning on line 218 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L217-L218

Added lines #L217 - L218 were not covered by tests
logger_, clock, 5000,
"Current steering angle rate is %.2f Hz. The sensor requires a rate in the range of %dHz to "
"%dHz",
estimated_hz, min_odometry_hz, max_odometry_hz);
}

Check warning on line 223 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L223

Added line #L223 was not covered by tests

constexpr float rad_to_deg = 180.f / M_PI;
hw_interface_->set_steering_angle_front_axle(rad_to_deg * msg->data);
}
Expand Down Expand Up @@ -289,9 +354,38 @@
const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetRadarParameters::Response>
response)
{
using Request = continental_srvs::srv::ContinentalArs548SetRadarParameters::Request;

uint8_t frequency_slot = 0;
uint8_t hcc = 0;

if (request->frequency_band == Request::FREQUENCY_BAND_LOW) {
frequency_slot = nebula::drivers::continental_ars548::frequency_slot_low;
} else if (request->frequency_band == Request::FREQUENCY_BAND_MID) {
frequency_slot = nebula::drivers::continental_ars548::frequency_slot_mid;
} else if (request->frequency_band == Request::FREQUENCY_BAND_HIGH) {
frequency_slot = nebula::drivers::continental_ars548::frequency_slot_high;
} else {
RCLCPP_ERROR(logger_, "Invalid frequency_band value");
response->success = false;
response->message = "Invalid frequency_band value";
return;

Check warning on line 372 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L369-L372

Added lines #L369 - L372 were not covered by tests
}

if (request->country_code == Request::COUNTRY_CODE_WORLDWIDE) {
hcc = nebula::drivers::continental_ars548::hcc_worldwide;
} else if (request->country_code == Request::COUNTRY_CODE_JAPAN) {
hcc = nebula::drivers::continental_ars548::hcc_japan;
} else {
RCLCPP_ERROR(logger_, "Invalid country_code value");
response->success = false;
response->message = "Invalid country_code value";
return;

Check warning on line 383 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L380-L383

Added lines #L380 - L383 were not covered by tests
}

auto result = hw_interface_->set_radar_parameters(
request->maximum_distance, request->frequency_slot, request->cycle_time, request->time_slot,
request->country_code, request->powersave_standstill);
request->maximum_distance, frequency_slot, request->cycle_time_ms, request->time_slot_ms, hcc,
request->powersave_standstill);

Check warning on line 388 in nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp#L387-L388

Added lines #L387 - L388 were not covered by tests

response->success = result == Status::OK;
response->message = util::to_string(result);
Expand Down
Loading