Skip to content

Commit

Permalink
Formatting changes
Browse files Browse the repository at this point in the history
  • Loading branch information
adriaroig authored and saikishor committed Apr 24, 2024
1 parent 58c2b85 commit 1ffd799
Showing 1 changed file with 8 additions and 8 deletions.
16 changes: 8 additions & 8 deletions hardware_interface/test/test_component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_one_interface)
EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits);
EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5));
EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5));
if(strcmp(joint, joint2_name) == 0)
if (strcmp(joint, joint2_name) == 0)
{
EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5));
EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5));
Expand Down Expand Up @@ -216,7 +216,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_multi_interface
// effort and velocity limits won't change as they are above the main URDF hard limits
EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5));
EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5));
if(strcmp(joint, joint2_name) == 0)
if (strcmp(joint, joint2_name) == 0)
{
EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5));
EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5));
Expand Down Expand Up @@ -284,7 +284,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_sens
EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits);
EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5));
EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5));
if(strcmp(joint, joint2_name) == 0)
if (strcmp(joint, joint2_name) == 0)
{
EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5));
EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5));
Expand Down Expand Up @@ -337,7 +337,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_exte
EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits);
EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5));
EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5));
if(strcmp(joint, joint2_name) == 0)
if (strcmp(joint, joint2_name) == 0)
{
EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5));
EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5));
Expand Down Expand Up @@ -424,7 +424,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot
EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits);
EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5));
EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5));
if(strcmp(joint, joint2_name) == 0)
if (strcmp(joint, joint2_name) == 0)
{
EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5));
EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5));
Expand Down Expand Up @@ -511,7 +511,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot
// effort and velocity limits won't change as they are above the main URDF hard limits
EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5));
EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5));
if(strcmp(joint, joint2_name) == 0)
if (strcmp(joint, joint2_name) == 0)
{
EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5));
EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.5, 1e-5));
Expand Down Expand Up @@ -580,7 +580,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot
// effort and velocity limits won't change as they are above the main URDF hard limits
EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5));
EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5));
if(strcmp(joint, joint2_name) == 0)
if (strcmp(joint, joint2_name) == 0)
{
EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5));
EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.5, 1e-5));
Expand Down Expand Up @@ -807,7 +807,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_gpio
EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits);
EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5));
EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5));
if(strcmp(joint, joint2_name) == 0)
if (strcmp(joint, joint2_name) == 0)
{
EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5));
EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5));
Expand Down

0 comments on commit 1ffd799

Please sign in to comment.