Skip to content

Commit

Permalink
Fix cpplint errors
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carlstrom <[email protected]>
  • Loading branch information
InvincibleRMC committed Jan 16, 2025
1 parent 3eb44b9 commit ee9adee
Showing 1 changed file with 8 additions and 7 deletions.
15 changes: 8 additions & 7 deletions mavros_extras/src/plugins/landing_target.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -464,7 +464,7 @@ class LandingTargetPlugin : public plugin::Plugin,
Eigen::Vector3d position = Eigen::Vector3d::Zero();
Eigen::Quaterniond orientation = Eigen::Quaterniond::Identity();
bool position_valid = false;

const auto data_frame = static_cast<MAV_FRAME>(req->frame);
switch(data_frame) {
case MAV_FRAME::LOCAL_NED: {
Expand All @@ -477,28 +477,29 @@ class LandingTargetPlugin : public plugin::Plugin,
}
case MAV_FRAME::BODY_FRD: {
position = ftf::transform_frame_baselink_aircraft(Eigen::Vector3d(tr.translation()));
orientation = ftf::transform_orientation_baselink_aircraft(Eigen::Quaterniond(tr.rotation()));
orientation = ftf::transform_orientation_baselink_aircraft(
Eigen::Quaterniond(tr.rotation()));
position_valid = true;
break;
}
default: {
//Raise a warning if a non-zero frame value is provided
//XXX: This is no ideal given that "0" is "MAV_FRAME::GLOBAL"
// Raise a warning if a non-zero frame value is provided
// XXX: This is no ideal given that "0" is "MAV_FRAME::GLOBAL"
// however this would be the "default value" for anyone
// using this interface without setting frame correctly
// using this interface without setting frame correctly
//
// The better option would be to expose "position_valid"
// in mavros_msgs::msg::LandingTarget, but this will at
// least allow people to use the angle interface without
// getting a constant error stream.
if(data_frame != MAV_FRAME::GLOBAL)
if(data_frame != MAV_FRAME::GLOBAL)
RCLCPP_WARN_STREAM(
get_logger(),
"LT: Landing target frame '" << req->frame << "' is not supported"
);
}
}

landing_target(
rclcpp::Time(req->header.stamp).nanoseconds() / 1000,
req->target_num,
Expand Down

0 comments on commit ee9adee

Please sign in to comment.