Skip to content

Commit

Permalink
chore(ars548): revert erroneously committed case style changes
Browse files Browse the repository at this point in the history
  • Loading branch information
mojomex authored Sep 6, 2024
1 parent 529c9bd commit 7abe20f
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class ContinentalARS548HwInterfaceWrapper

/// @brief Callback to send the steering angle information to the radar device
/// @param msg The steering angle message
void steeringAngleCallback(const std_msgs::msg::Float32::SharedPtr msg);
void SteeringAngleCallback(const std_msgs::msg::Float32::SharedPtr msg);

/// @brief Service callback to set the new sensor ip
/// @param request service request
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,7 @@ void ContinentalARS548HwInterfaceWrapper::SensorInterfaceStart()
steering_angle_sub_ = parent_node_->create_subscription<std_msgs::msg::Float32>(
"steering_angle_input", rclcpp::SensorDataQoS(),
std::bind(
&::nebula::ros::ContinentalARS548HwInterfaceWrapper::steeringAngleCallback, this,
std::placeholders::_1));
&ContinentalARS548HwInterfaceWrapper::SteeringAngleCallback, this, std::placeholders::_1));

set_network_configuration_service_server_ =
parent_node_->create_service<continental_srvs::srv::ContinentalArs548SetNetworkConfiguration>(
Expand Down Expand Up @@ -152,7 +151,7 @@ void ContinentalARS548HwInterfaceWrapper::AccelerationCallback(
hw_interface_->SetAccelerationLongitudinalCog(msg->accel.accel.linear.x);
}

void ContinentalARS548HwInterfaceWrapper::steeringAngleCallback(
void ContinentalARS548HwInterfaceWrapper::SteeringAngleCallback(
const std_msgs::msg::Float32::SharedPtr msg)
{
constexpr float rad_to_deg = 180.f / M_PI;
Expand Down

0 comments on commit 7abe20f

Please sign in to comment.