Skip to content

Commit

Permalink
lib #358: cleanup.
Browse files Browse the repository at this point in the history
Replace UAS::getYaw() with UAS::quaternion_get_yaw().
  • Loading branch information
vooon committed Aug 4, 2015
1 parent 8cfdd89 commit 87016b5
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 11 deletions.
7 changes: 1 addition & 6 deletions mavros/include/mavros/mavros_uas.h
Original file line number Diff line number Diff line change
Expand Up @@ -371,17 +371,12 @@ class UAS {
yaw = rpy.z();
}

static double quaternion_get_yaw(const Eigen::Quaterniond &q);

/**
* @brief Get Yaw angle from quaternion
*
* Replacement function for @a tf::getYaw()
*/
static inline double getYaw(const Eigen::Quaterniond &q) {
//return quaternion_to_rpy(q).z();
return quaternion_get_yaw(q);
}
static double quaternion_get_yaw(const Eigen::Quaterniond &q);

/**
* @brief Store Quaternion to MAVLink float[4] format
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/setpoint_position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ class SetpointPositionPlugin : public MavRosPlugin,
p.x(), p.y(), p.z(),
0.0, 0.0, 0.0,
0.0, 0.0, 0.0,
UAS::getYaw(q), 0.0);
UAS::quaternion_get_yaw(q), 0.0);
}

/* -*- callbacks -*- */
Expand Down
8 changes: 4 additions & 4 deletions mavros/test/test_quaternion_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,16 +112,16 @@ TEST(UAS, quaternion_to_rpy__pm_pi)

// UAS::quaternion_to_rpy() is not compatible with tf2::Matrix3x3(q).getRPY()

TEST(UAS, getYaw__123)
TEST(UAS, quaternion_get_yaw__123)
{
// with pich >= pi/2 got incorrect result.
// so 1, 2, 3 rad (57, 115, 172 deg) replaced with 60, 89, 172 deg
auto q = UAS::quaternion_from_rpy(60.0 * deg_to_rad, 89.0 * deg_to_rad, 3.0);

EXPECT_NEAR(3.0, UAS::getYaw(q), epsilon);
EXPECT_NEAR(3.0, UAS::quaternion_get_yaw(q), epsilon);
}

TEST(UAS, getYaw__pm_pi)
TEST(UAS, quaternion_get_yaw__pm_pi)
{
// in degrees
const ssize_t min = -180;
Expand All @@ -140,7 +140,7 @@ TEST(UAS, getYaw__pm_pi)
SCOPED_TRACE(ss.str());

auto q1 = UAS::quaternion_from_rpy(expected);
double q1_yaw = UAS::getYaw(q1);
double q1_yaw = UAS::quaternion_get_yaw(q1);

EXPECT_NEAR(expected.z(), q1_yaw, epsilon);
}
Expand Down

0 comments on commit 87016b5

Please sign in to comment.