Skip to content

Commit

Permalink
Switch from deprecated signature to const shared_ptr reference while …
Browse files Browse the repository at this point in the history
…still supporting efficient intra-process communication

See ros2/rclcpp#1598.

Signed-off-by: Sarah Huber <[email protected]>
  • Loading branch information
shu-beg authored and rcp1-beg committed May 14, 2024
1 parent 3792722 commit 8e616f4
Show file tree
Hide file tree
Showing 9 changed files with 9 additions and 9 deletions.
2 changes: 1 addition & 1 deletion off_highway_can/include/off_highway_can/receiver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ class Receiver : public rclcpp::Node
*
* \param frame ROS CAN frame
*/
void callback_can(const can_msgs::msg::Frame::SharedPtr frame);
void callback_can(const can_msgs::msg::Frame::ConstSharedPtr & frame);

/**
* \brief Returns message definitions of configured CAN messages
Expand Down
2 changes: 1 addition & 1 deletion off_highway_can/src/receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ void Receiver::callback_watchdog()
}
}

void Receiver::callback_can(const can_msgs::msg::Frame::SharedPtr frame)
void Receiver::callback_can(const can_msgs::msg::Frame::ConstSharedPtr & frame)
{
#if (RCLCPP_LOG_MIN_SEVERITY <= RCLCPP_LOG_MIN_SEVERITY_DEBUG)
using std::chrono::steady_clock;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ class DefaultConverter : public Converter
* \brief Subscription callback on ego vehicle data
*/
void on_ego_vehicle_data(
const off_highway_premium_radar_msgs::msg::EgoVehicleInput::SharedPtr msg);
const off_highway_premium_radar_msgs::msg::EgoVehicleInput::ConstSharedPtr & msg);

/**
* \brief Send measurement cycle sync (triggered by timer)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -189,7 +189,7 @@ void DefaultConverter::on_sensor_dtc_information(const SensorDTCInformation & da


void DefaultConverter::on_ego_vehicle_data(
const off_highway_premium_radar_msgs::msg::EgoVehicleInput::SharedPtr msg)
const off_highway_premium_radar_msgs::msg::EgoVehicleInput::ConstSharedPtr & msg)
{
// TODO(rcp1-beg) Check the x velocity range [-100, 100]?
EgoVehicleInput d;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -305,7 +305,7 @@ auto to_msg(const SensorDTCInformation & d, const rclcpp::Time stamp, const std:

// From ROS message
inline
auto from_msg(const msg::EgoVehicleInput::SharedPtr msg)
auto from_msg(const msg::EgoVehicleInput::ConstSharedPtr & msg)
{
const auto & x_velocity_variance = msg->vehicle_data.velocity.covariance[0];
if (x_velocity_variance < 0.0) {
Expand Down
2 changes: 1 addition & 1 deletion off_highway_radar/include/off_highway_radar/sender.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class Sender : public off_highway_can::Sender
*
* \param msg Received message data
*/
void callback_input(const RadarInput::SharedPtr msg);
void callback_input(const RadarInput::ConstSharedPtr & msg);

/**
* \brief Fill message definitions to encode frames of CAN node. Only stored definitions are sent.
Expand Down
2 changes: 1 addition & 1 deletion off_highway_radar/src/sender.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ Sender::Sender(const rclcpp::NodeOptions & options)
);
}

void Sender::callback_input(const RadarInput::SharedPtr msg)
void Sender::callback_input(const RadarInput::ConstSharedPtr & msg)
{
if (std::abs((now() - msg->header.stamp).seconds()) < allowed_age_) {
auto & v = messages_[ego_velocity_id_].signals["v"];
Expand Down
2 changes: 1 addition & 1 deletion off_highway_uss/include/off_highway_uss/sender.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class Sender : public off_highway_can::Sender
*
* \param msg Received message data
*/
void callback_input(const UssInput::SharedPtr msg);
void callback_input(const UssInput::ConstSharedPtr & msg);

/**
* \brief Fill message definitions to encode frames of CAN node. Only stored definitions are sent.
Expand Down
2 changes: 1 addition & 1 deletion off_highway_uss/src/sender.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ Sender::Sender(const rclcpp::NodeOptions & options)
);
}

void Sender::callback_input(const UssInput::SharedPtr msg)
void Sender::callback_input(const UssInput::ConstSharedPtr & msg)
{
if (std::abs((now() - msg->header.stamp).seconds()) < allowed_age_) {
auto & outside_temperature = messages_[outside_temperature_id_].signals["OutsideTemperature"];
Expand Down

0 comments on commit 8e616f4

Please sign in to comment.