Skip to content

Commit

Permalink
Support printing pose elements in degrees, added tests
Browse files Browse the repository at this point in the history
Signed-off-by: Aaron Chong <[email protected]>
  • Loading branch information
aaronchongth committed Aug 31, 2021
1 parent 6f148fa commit 9ac3504
Show file tree
Hide file tree
Showing 8 changed files with 235 additions and 72 deletions.
6 changes: 6 additions & 0 deletions include/sdf/Param.hh
Original file line number Diff line number Diff line change
Expand Up @@ -236,6 +236,12 @@ namespace sdf
/// \return True if the parameter has been set.
public: bool GetSet() const;

/// \brief Return true if the parameter ignores the parent element's
/// attributes, or if the parameter has no parent element.
/// \return True if the parameter ignores the parent element's attributes,
/// or if the parameter has no parent element.
public: bool IgnoresParentElementAttribute() const;

/// \brief Clone the parameter.
/// \return A new parameter that is the clone of this.
public: ParamPtr Clone() const;
Expand Down
13 changes: 12 additions & 1 deletion src/Param.cc
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,11 @@ std::string Param::GetAsString() const
{
StringStreamClassicLocale ss;

ss << ParamStreamer{ this->dataPtr->value };
if (this->dataPtr->strValue.has_value())
ss << this->dataPtr->strValue.value();
else
ss << ParamStreamer{ this->dataPtr->value };

return ss.str();
}

Expand Down Expand Up @@ -834,6 +838,13 @@ bool Param::GetSet() const
return this->dataPtr->set;
}

/////////////////////////////////////////////////
bool Param::IgnoresParentElementAttribute() const
{
const auto parentElement = this->dataPtr->parentElement.lock();
return !parentElement || this->dataPtr->ignoreParentAttributes;
}

/////////////////////////////////////////////////
bool Param::ValidateValue() const
{
Expand Down
51 changes: 51 additions & 0 deletions src/Param_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -704,6 +704,57 @@ TEST(Param, ReparsingAfterSetFromStringPose)
EXPECT_EQ(Pose(2, 3, 4, IGN_DTOR(0.5), IGN_DTOR(0.6), IGN_DTOR(0.7)), value);
}

/////////////////////////////////////////////////
TEST(Param, IgnoresParentElementAttribute)
{
{
// Without parent
sdf::Param doubleParam("key", "double", "1.0", false, "description");
EXPECT_TRUE(doubleParam.IgnoresParentElementAttribute());
}

{
// With parent
sdf::Param doubleParam("key", "double", "1.0", false, "description");
sdf::ElementPtr parentElement = std::make_shared<sdf::Element>();
doubleParam.SetParentElement(parentElement);
EXPECT_FALSE(doubleParam.IgnoresParentElementAttribute());
}

{
// Param from parent element
sdf::ElementPtr elem(new sdf::Element);
elem->SetName("double");
elem->AddValue("double", "0", true);

sdf::ParamPtr valParam = elem->GetValue();
ASSERT_NE(nullptr, valParam);
EXPECT_FALSE(valParam->IgnoresParentElementAttribute());
}

{
// With parent using Set and SetFromString
sdf::Param doubleParam("key", "double", "1.0", false, "description");
sdf::ElementPtr parentElement = std::make_shared<sdf::Element>();
doubleParam.SetParentElement(parentElement);
ASSERT_TRUE(doubleParam.Set<double>(23.4));
EXPECT_TRUE(doubleParam.IgnoresParentElementAttribute());

ASSERT_TRUE(doubleParam.SetFromString("34.5"));
EXPECT_FALSE(doubleParam.IgnoresParentElementAttribute());

ASSERT_TRUE(doubleParam.SetFromString("45.6", true));
EXPECT_TRUE(doubleParam.IgnoresParentElementAttribute());

ASSERT_TRUE(doubleParam.SetFromString("56.7", false));
EXPECT_FALSE(doubleParam.IgnoresParentElementAttribute());

ASSERT_TRUE(doubleParam.Set<double>(67.8));
EXPECT_TRUE(doubleParam.IgnoresParentElementAttribute());
}
}


/////////////////////////////////////////////////
/// Main
int main(int argc, char **argv)
Expand Down
32 changes: 16 additions & 16 deletions test/integration/include_custom_model_expected_output.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@
</box>
</geometry>
<material>
<ambient>0.5 0.5 1 1</ambient>
<diffuse>0.5 0.5 1 1</diffuse>
<specular>0 0 1 1</specular>
<ambient>0.5 0.5 1.0 1</ambient>
<diffuse>0.5 0.5 1.0 1</diffuse>
<specular>0.0 0.0 1.0 1</specular>
</material>
</visual>
<collision name='collision'>
Expand Down Expand Up @@ -72,12 +72,12 @@
<resolution>0.01</resolution>
</range>
</lidar>
<visualize>1</visualize>
<visualize>true</visualize>
<alwaysOn>1</alwaysOn>
</sensor> -->

<sensor name='camera' type='camera'>
<pose>-1.06 0 0 0 -0 3.14</pose>
<pose>-1.06 0 0 0 0 3.14</pose>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
Expand All @@ -92,15 +92,15 @@

<!-- removed -->
<!-- <always_on>1</always_on>
<visualize>1</visualize> -->
<visualize>true</visualize> -->

<update_rate>30</update_rate>
<topic>chassis/camera</topic>
</sensor>

<!-- added -->
<visual name='camera_visual'>
<pose>-1.06 0 0 0 -0 3.14</pose>
<pose>-1.06 0 0 0 0 3.14</pose>
<geometry>
<box>
<size>0.1 0.1 0.1</size>
Expand All @@ -110,7 +110,7 @@
</link>

<link name='top'>
<pose>0.6 0 0.7 0 -0 0</pose>
<pose>0.6 0 0.7 0 0 0</pose>

<collision name='top_collision'>
<geometry>
Expand Down Expand Up @@ -170,7 +170,7 @@
</collision> -->

<visual name='camera_visual'>
<pose>-0.2 0 0.3 0 -0 3.14</pose>
<pose>-0.2 0 0.3 0 0 3.14</pose>

<geometry>
<sphere>
Expand Down Expand Up @@ -205,13 +205,13 @@
</visual>

<sensor name='cam' type='camera' custom:test='hello'>
<pose relative_to='__model__'>0.1 0.2 0.3 0 -0 0</pose>
<pose relative_to='__model__'>0.1 0.2 0.3 0 0 0</pose>
<camera name='top_camera'>
<!-- modified with above -->
<!-- <sensor name='camera' type='camera'>
<pose>-0.2 0 0.3 0 -0 0</pose>
<camera> -->
<horizontal_fov>1.047</horizontal_fov>
<horizontal_fov>1.0469999999999999</horizontal_fov>
<image>
<width>1280</width>
<!-- modified with above -->
Expand All @@ -232,7 +232,7 @@
<update_rate>20</update_rate>
<!-- modified with above -->
<!-- <update_rate>30</update_rate> -->
<visualize>1</visualize>
<visualize>true</visualize>
<topic>top/cam</topic>
<!-- modified with above -->
<!-- <topic>top/camera</topic> -->
Expand Down Expand Up @@ -332,7 +332,7 @@

</link>
<link name='caster'>
<pose relative_to='right_wheel'>0 0 0 0 0 0</pose>
<pose relative_to='right_wheel'>0 0 0 0 -0 0</pose>
<!-- modified with above -->
<!-- <pose relative_to='__model__'>-0.957138 -0 -0.125 0 -0 0</pose> -->
<inertial>
Expand Down Expand Up @@ -408,7 +408,7 @@
</joint>

<model name='nested_models'>
<pose relative_to='caster'>1 1 1 0 -0 0</pose>
<pose relative_to='caster'>1 1 1 0 0 0</pose>
<!-- modified with above -->
<!-- <pose relative_to='__model__'>0 0 0 0 -0 0</pose> -->
<model name='model1'>
Expand All @@ -429,7 +429,7 @@

<!-- added -->
<link name='new_link'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 0</pose>
<sensor name='camera_sensor' type='camera'>
<camera>
<horizontal_fov>1.047</horizontal_fov>
Expand All @@ -444,7 +444,7 @@
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>1</visualize>
<visualize>true</visualize>
</sensor>
</link>

Expand Down
Loading

0 comments on commit 9ac3504

Please sign in to comment.