Skip to content

Commit 7a64c81

Browse files
committed
mavros: fix indentation
1 parent a20c837 commit 7a64c81

File tree

4 files changed

+40
-35
lines changed

4 files changed

+40
-35
lines changed

mavros/include/mavros/mavros_uas.hpp

Lines changed: 27 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -379,27 +379,33 @@ class UAS : public rclcpp::Node
379379
const std::string & frame_id, const std::string & child_id,
380380
const Eigen::Affine3d & tr);
381381

382-
inline void set_base_link_frame_id(const std::string frame_id) {
383-
base_link_frame_id = frame_id;
384-
}
385-
inline void set_odom_frame_id(const std::string frame_id) {
386-
odom_frame_id = frame_id;
387-
}
388-
inline void set_map_frame_id(const std::string frame_id) {
389-
map_frame_id = frame_id;
390-
}
391-
inline std::string get_base_link_frame_id() {
392-
return base_link_frame_id;
393-
}
394-
inline std::string get_odom_frame_id() {
395-
return odom_frame_id;
396-
}
397-
inline std::string get_map_frame_id() {
398-
return map_frame_id;
399-
}
400-
401-
//! Publish helper TFs used for frame transformation in the odometry plugin
402-
void setup_static_tf();
382+
inline void set_base_link_frame_id(const std::string frame_id)
383+
{
384+
base_link_frame_id = frame_id;
385+
}
386+
inline void set_odom_frame_id(const std::string frame_id)
387+
{
388+
odom_frame_id = frame_id;
389+
}
390+
inline void set_map_frame_id(const std::string frame_id)
391+
{
392+
map_frame_id = frame_id;
393+
}
394+
inline std::string get_base_link_frame_id()
395+
{
396+
return base_link_frame_id;
397+
}
398+
inline std::string get_odom_frame_id()
399+
{
400+
return odom_frame_id;
401+
}
402+
inline std::string get_map_frame_id()
403+
{
404+
return map_frame_id;
405+
}
406+
407+
//! Publish helper TFs used for frame transformation in the odometry plugin
408+
void setup_static_tf();
403409

404410
/* -*- time sync -*- */
405411

mavros/src/lib/uas_data.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020
#include "mavros/utils.hpp"
2121
#include "mavros/px4_custom_mode.hpp"
2222

23-
<<<<<<< HEAD
2423
using namespace mavros::uas; // NOLINT
2524

2625
std::once_flag Data::init_flag;

mavros/src/lib/uas_tf.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -50,15 +50,15 @@ void UAS::publish_static_transform(
5050

5151
void UAS::setup_static_tf()
5252
{
53-
std::vector<geometry_msgs::TransformStamped> transform_vector;
54-
add_static_transform(map_frame_id, map_frame_id+"_ned",
53+
std::vector<geometry_msgs::TransformStamped> transform_vector;
54+
add_static_transform(map_frame_id, map_frame_id + "_ned",
5555
Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, M_PI_2)),
5656
transform_vector);
57-
add_static_transform(odom_frame_id, odom_frame_id+"_ned",
57+
add_static_transform(odom_frame_id, odom_frame_id + "_ned",
5858
Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, M_PI_2)),
5959
transform_vector);
60-
add_static_transform(base_link_frame_id, base_link_frame_id+"_frd",
60+
add_static_transform(base_link_frame_id, base_link_frame_id + "_frd",
6161
Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, 0)),
6262
transform_vector);
63-
tf2_static_broadcaster.sendTransform(transform_vector);
63+
tf2_static_broadcaster.sendTransform(transform_vector);
6464
}

mavros_extras/src/plugins/odom.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ class OdometryPlugin : public plugin::Plugin
5757

5858
explicit OdometryPlugin(plugin::UASPtr uas_)
5959
: Plugin(uas_, "odometry"),
60-
fcu_map_id_des("map"),
60+
fcu_map_id_des("map"),
6161
fcu_odom_parent_id_des("map"),
6262
fcu_odom_child_id_des("base_link")
6363
{
@@ -99,9 +99,9 @@ class OdometryPlugin : public plugin::Plugin
9999
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr odom_pub;
100100
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub;
101101

102-
std::string fcu_odom_parent_id_des; //!< desired orientation of the fcu odometry message's parent frame
103-
std::string fcu_odom_child_id_des; //!< desired orientation of the fcu odometry message's child frame
104-
std::string fcu_map_id_des; //!< desired orientation of the fcu map frame
102+
std::string fcu_odom_parent_id_des; //!< desired orientation of the fcu odometry message's parent frame
103+
std::string fcu_odom_child_id_des; //!< desired orientation of the fcu odometry message's child frame
104+
std::string fcu_map_id_des; //!< desired orientation of the fcu map frame
105105

106106
/**
107107
* @brief Lookup static transform with error handling
@@ -149,11 +149,11 @@ class OdometryPlugin : public plugin::Plugin
149149
Eigen::Affine3d tf_parent2parent_des;
150150
Eigen::Affine3d tf_child2child_des;
151151

152-
lookup_static_transform(
153-
fcu_map_id_des, fcu_map_id_des+"_ned",
152+
lookup_static_transform(
153+
fcu_map_id_des, fcu_map_id_des + "_ned",
154154
tf_parent2parent_des);
155-
lookup_static_transform(
156-
fcu_odom_child_id_des, fcu_odom_child_id_des+"_frd",
155+
lookup_static_transform(
156+
fcu_odom_child_id_des, fcu_odom_child_id_des + "_frd",
157157
tf_child2child_des);
158158

159159
//! Build 6x6 pose covariance matrix to be transformed and sent

0 commit comments

Comments
 (0)