Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add error handling for JointAxis::SetXyz and remove use of use_parent_model_frame #288

Merged
merged 4 commits into from
Sep 2, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/workflows/ci-bionic.yml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
name: Ubuntu CI

on: [push]
on: [push, pull_request]

jobs:
bionic-ci:
Expand Down
21 changes: 4 additions & 17 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -570,14 +570,6 @@ msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in)
{
msgs::Axis out;
msgs::Set(out.mutable_xyz(), _in.Xyz());
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
out.set_use_parent_model_frame(_in.UseParentModelFrame());
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
out.set_xyz_expressed_in(_in.XyzExpressedIn());
out.set_damping(_in.Damping());
out.set_friction(_in.Friction());
Expand Down Expand Up @@ -606,15 +598,10 @@ template<>
sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in)
{
sdf::JointAxis out;
out.SetXyz(msgs::Convert(_in.xyz()));
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
out.SetUseParentModelFrame(_in.use_parent_model_frame());
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
sdf::Errors errors = out.SetXyz(msgs::Convert(_in.xyz()));
for (const auto &err : errors) {
ignerr << err.Message() << std::endl;
}
out.SetXyzExpressedIn(_in.xyz_expressed_in());
out.SetDamping(_in.damping());
out.SetFriction(_in.friction());
Expand Down
6 changes: 3 additions & 3 deletions src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -434,7 +434,7 @@ TEST(Conversions, Inertial)
TEST(Conversions, JointAxis)
{
sdf::JointAxis jointAxis;
jointAxis.SetXyz(math::Vector3d(1, 2, 3));
EXPECT_TRUE(jointAxis.SetXyz(math::Vector3d(1, 2, 3)).empty());
jointAxis.SetXyzExpressedIn("__model__");
jointAxis.SetDamping(0.1);
jointAxis.SetFriction(0.2);
Expand All @@ -444,7 +444,7 @@ TEST(Conversions, JointAxis)
jointAxis.SetMaxVelocity(0.6);

auto axisMsg = convert<msgs::Axis>(jointAxis);
EXPECT_EQ(math::Vector3d(1, 2, 3), msgs::Convert(axisMsg.xyz()));
EXPECT_EQ(math::Vector3d(1, 2, 3).Normalized(), msgs::Convert(axisMsg.xyz()));
EXPECT_DOUBLE_EQ(0.1, axisMsg.damping());
EXPECT_DOUBLE_EQ(0.2, axisMsg.friction());
EXPECT_DOUBLE_EQ(0.3, axisMsg.limit_lower());
Expand All @@ -454,7 +454,7 @@ TEST(Conversions, JointAxis)
EXPECT_EQ(axisMsg.xyz_expressed_in(), "__model__");

auto newJointAxis = convert<sdf::JointAxis>(axisMsg);
EXPECT_EQ(math::Vector3d(1, 2, 3), newJointAxis.Xyz());
EXPECT_EQ(math::Vector3d(1, 2, 3).Normalized(), newJointAxis.Xyz());
EXPECT_DOUBLE_EQ(0.1, newJointAxis.Damping());
EXPECT_DOUBLE_EQ(0.2, newJointAxis.Friction());
EXPECT_DOUBLE_EQ(0.3, newJointAxis.Lower());
Expand Down
4 changes: 2 additions & 2 deletions test/integration/components.cc
Original file line number Diff line number Diff line change
Expand Up @@ -525,7 +525,7 @@ TEST_F(ComponentsTest, Joint)
TEST_F(ComponentsTest, JointAxis)
{
auto data1 = sdf::JointAxis();
data1.SetXyz(math::Vector3d(1, 2, 3));
EXPECT_TRUE(data1.SetXyz(math::Vector3d(1, 2, 3)).empty());
data1.SetXyzExpressedIn("__model__");
data1.SetDamping(0.1);
data1.SetFriction(0.2);
Expand All @@ -551,7 +551,7 @@ TEST_F(ComponentsTest, JointAxis)
components::JointAxis comp3;
comp3.Deserialize(istr);

EXPECT_EQ(math::Vector3d(1, 2, 3), comp3.Data().Xyz());
EXPECT_EQ(math::Vector3d(1, 2, 3).Normalized(), comp3.Data().Xyz());
EXPECT_DOUBLE_EQ(0.1, comp3.Data().Damping());
EXPECT_DOUBLE_EQ(0.2, comp3.Data().Friction());
EXPECT_DOUBLE_EQ(0.3, comp3.Data().Lower());
Expand Down