Skip to content

Commit

Permalink
fix compile warning (#305)
Browse files Browse the repository at this point in the history
  • Loading branch information
rsasaki0109 committed Aug 22, 2023
1 parent 425ffd8 commit 6685ccf
Show file tree
Hide file tree
Showing 10 changed files with 22 additions and 22 deletions.
10 changes: 5 additions & 5 deletions eagleye_rt/src/rolling_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,27 +46,27 @@ struct RollingStatus _rolling_status;

static bool _use_can_less_mode;

void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstPtr msg)
void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr msg)
{
_velocity_msg = *msg;
}

void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstPtr msg)
void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstSharedPtr msg)
{
_velocity_status_msg = *msg;
}

void yaw_rate_offset_stop_callback(const eagleye_msgs::msg::YawrateOffset::ConstPtr msg)
void yaw_rate_offset_stop_callback(const eagleye_msgs::msg::YawrateOffset::ConstSharedPtr msg)
{
_yaw_rate_offset_stop_msg = *msg;
}

void yaw_rate_offset_2nd_callback(const eagleye_msgs::msg::YawrateOffset::ConstPtr msg)
void yaw_rate_offset_2nd_callback(const eagleye_msgs::msg::YawrateOffset::ConstSharedPtr msg)
{
_yaw_rate_offset_2nd_msg = *msg;
}

void imu_callback(const sensor_msgs::msg::Imu::ConstPtr msg)
void imu_callback(const sensor_msgs::msg::Imu::ConstSharedPtr msg)
{
if(_use_can_less_mode && !_velocity_status_msg.status.enabled_status) return;
_imu_msg = *msg;
Expand Down
4 changes: 2 additions & 2 deletions eagleye_rt/src/rtk_heading_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ struct RtkHeadingStatus heading_status;

static bool use_can_less_mode;

void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstPtr msg)
void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr msg)
{
velocity = *msg;
}
Expand All @@ -60,7 +60,7 @@ void gga_callback(const nmea_msgs::msg::Gpgga::ConstSharedPtr msg)
gga = *msg;
}

void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstPtr msg)
void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstSharedPtr msg)
{
velocity_status = *msg;
}
Expand Down
4 changes: 2 additions & 2 deletions eagleye_rt/src/slip_angle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,12 @@ struct SlipangleParameter slip_angle_parameter;

static bool use_can_less_mode;

void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstPtr msg)
void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr msg)
{
velocity = *msg;
}

void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstPtr msg)
void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstSharedPtr msg)
{
velocity_status = *msg;
}
Expand Down
2 changes: 1 addition & 1 deletion eagleye_rt/src/slip_coefficient_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr ms
}
}

void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstPtr msg)
void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstSharedPtr msg)
{
velocity_status = *msg;
}
Expand Down
2 changes: 1 addition & 1 deletion eagleye_rt/src/smoothing_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr ms
velocity = *msg;
}

void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstPtr msg)
void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstSharedPtr msg)
{
velocity_status = *msg;
}
Expand Down
4 changes: 2 additions & 2 deletions eagleye_rt/src/tf_converted_imu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class TFConvertedIMU: public rclcpp::Node

std::string tf_base_link_frame_;

void imu_callback(const sensor_msgs::msg::Imu::ConstPtr msg);
void imu_callback(const sensor_msgs::msg::Imu::ConstSharedPtr msg);

};

Expand Down Expand Up @@ -95,7 +95,7 @@ TFConvertedIMU::TFConvertedIMU() : Node("eagleye_tf_converted_imu"),

TFConvertedIMU::~TFConvertedIMU(){};

void TFConvertedIMU::imu_callback(const sensor_msgs::msg::Imu::ConstPtr msg)
void TFConvertedIMU::imu_callback(const sensor_msgs::msg::Imu::ConstSharedPtr msg)
{
imu_ = *msg;
tf_converted_imu_.header = imu_.header;
Expand Down
2 changes: 1 addition & 1 deletion eagleye_rt/src/trajectory_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ void correction_velocity_callback(const geometry_msgs::msg::TwistStamped::ConstS
correction_velocity = *msg;
}

void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstPtr msg)
void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstSharedPtr msg)
{
velocity_status = *msg;
}
Expand Down
8 changes: 4 additions & 4 deletions eagleye_rt/src/twist_relay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ class TwistRelay: public rclcpp::Node
rclcpp::Logger logger_;
rclcpp::Clock clock_;

void twist_callback(const geometry_msgs::msg::TwistStamped::ConstPtr msg);
void twist_with_covariance_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstPtr msg);
void twist_callback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr msg);
void twist_with_covariance_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr msg);

};

Expand Down Expand Up @@ -90,12 +90,12 @@ TwistRelay::TwistRelay() : Node("eagleye_twist_relay"),

TwistRelay::~TwistRelay(){};

void TwistRelay::twist_callback(const geometry_msgs::msg::TwistStamped::ConstPtr msg)
void TwistRelay::twist_callback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr msg)
{
pub_->publish(*msg);
};

void TwistRelay::twist_with_covariance_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstPtr msg)
void TwistRelay::twist_with_covariance_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr msg)
{
geometry_msgs::msg::TwistStamped twist;
twist.header.stamp = msg->header.stamp;
Expand Down
6 changes: 3 additions & 3 deletions eagleye_rt/src/velocity_estimator_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,17 +48,17 @@ static std::string yaml_file;
static std::string subscribe_rtklib_nav_topic_name = "gnss/rtklib_nav";
static std::string subscribe_gga_topic_name = "gnss/gga";

void rtklib_nav_callback(const rtklib_msgs::msg::RtklibNav::ConstPtr msg)
void rtklib_nav_callback(const rtklib_msgs::msg::RtklibNav::ConstSharedPtr msg)
{
rtklib_nav_msg = *msg;
}

void gga_callback(const nmea_msgs::msg::Gpgga::ConstPtr msg)
void gga_callback(const nmea_msgs::msg::Gpgga::ConstSharedPtr msg)
{
gga_msg = *msg;
}

void imu_callback(const sensor_msgs::msg::Imu::ConstPtr msg)
void imu_callback(const sensor_msgs::msg::Imu::ConstSharedPtr msg)
{
imu_msg = *msg;

Expand Down
2 changes: 1 addition & 1 deletion eagleye_rt/src/yaw_rate_offset_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ void velocity_callback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr ms
_velocity = *msg;
}

void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstPtr msg)
void velocity_status_callback(const eagleye_msgs::msg::StatusStamped::ConstSharedPtr msg)
{
_velocity_status = *msg;
}
Expand Down

0 comments on commit 6685ccf

Please sign in to comment.