diff --git a/.github/workflows/ci-bionic.yml b/.github/workflows/ci-bionic.yml index c708c1325e..50b9c56611 100644 --- a/.github/workflows/ci-bionic.yml +++ b/.github/workflows/ci-bionic.yml @@ -1,6 +1,6 @@ name: Ubuntu CI -on: [push] +on: [push, pull_request] jobs: bionic-ci: diff --git a/src/Conversions.cc b/src/Conversions.cc index 778fd94d19..b5cc4b1ca5 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -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()); @@ -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()); diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index 2227692e6d..b25232fed2 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -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); @@ -444,7 +444,7 @@ TEST(Conversions, JointAxis) jointAxis.SetMaxVelocity(0.6); auto axisMsg = convert(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()); @@ -454,7 +454,7 @@ TEST(Conversions, JointAxis) EXPECT_EQ(axisMsg.xyz_expressed_in(), "__model__"); auto newJointAxis = convert(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()); diff --git a/test/integration/components.cc b/test/integration/components.cc index 2f99c6d4ef..2b593e7c54 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -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); @@ -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());