Skip to content

Commit

Permalink
Addressing PR comments
Browse files Browse the repository at this point in the history
Signed-off-by: Marcos Wagner <[email protected]>
  • Loading branch information
WagnerMarcos committed Jul 22, 2021
1 parent 66bb5cf commit 55018ee
Show file tree
Hide file tree
Showing 5 changed files with 295 additions and 197 deletions.
147 changes: 97 additions & 50 deletions src/ModelCommandAPI_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -117,72 +117,93 @@ TEST(ModelCommandAPI, Commands)
"\nRequesting state for world [diff_drive]...\n\n"
"Model: [8]\n"
" - Name: vehicle_blue\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 2.000000 | 0.325000]\n"
" [0.000000 | 0.000000 | 0.000000]\n"
"\n"
" - Link [9]\n"
" - Name: chassis\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [1.143950]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [1.143950]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.126164 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.416519 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.481014]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [-0.151427 | 0.000000 | 0.175000]\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Link [12]\n"
" - Name: left_wheel\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [2.000000]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [2.000000]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.145833 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.145833 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.125000]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.554283 | 0.625029 | -0.025000]\n"
" [-1.570700 | 0.000000 | 0.000000]\n"
" - Link [15]\n"
" - Name: right_wheel\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [2.000000]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [2.000000]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.145833 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.145833 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.125000]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.554282 | -0.625029 | -0.025000]\n"
" [-1.570700 | 0.000000 | 0.000000]\n"
" - Link [18]\n"
" - Name: caster\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [1.000000]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [1.000000]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.100000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.100000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.100000]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [-0.957138 | 0.000000 | -0.125000]\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Joint [21]\n"
" - Name: left_wheel_joint\n"
" - Parent: vehicle_blue [8]\n"
" - Joint type: revolute\n"
" - Parent Link: [left_wheel]\n"
" - Child Link: [chassis]\n"
" - Type: revolute\n"
" - Parent Link: left_wheel\n"
" - Child Link: chassis\n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Axis unit vector [ XYZ ]: \n"
" [0 | 0 | 1]\n"
" - Joint [22]\n"
" - Name: right_wheel_joint\n"
" - Parent: vehicle_blue [8]\n"
" - Joint type: revolute\n"
" - Parent Link: [right_wheel]\n"
" - Child Link: [chassis]\n"
" - Type: revolute\n"
" - Parent Link: right_wheel\n"
" - Child Link: chassis\n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Axis unit vector [ XYZ ]: \n"
" [0 | 0 | 1]\n"
" - Joint [23]\n"
" - Name: caster_wheel\n"
" - Parent: vehicle_blue [8]\n"
" - Joint type: ball\n"
" - Parent Link: [caster]\n"
" - Child Link: [chassis]\n";
" - Type: ball\n"
" - Parent Link: caster\n"
" - Child Link: chassis\n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.000000]\n";
EXPECT_EQ(expectedOutput, output);
}

Expand All @@ -195,7 +216,7 @@ TEST(ModelCommandAPI, Commands)
"\nRequesting state for world [diff_drive]...\n\n"
"Model: [8]\n"
" - Name: vehicle_blue\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 2.000000 | 0.325000]\n"
" [0.000000 | 0.000000 | 0.000000]\n\n";
EXPECT_EQ(expectedOutput, output);
Expand All @@ -212,45 +233,53 @@ TEST(ModelCommandAPI, Commands)
" - Link [9]\n"
" - Name: chassis\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [1.143950]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [1.143950]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.126164 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.416519 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.481014]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [-0.151427 | 0.000000 | 0.175000]\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Link [12]\n"
" - Name: left_wheel\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [2.000000]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [2.000000]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.145833 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.145833 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.125000]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.554283 | 0.625029 | -0.025000]\n"
" [-1.570700 | 0.000000 | 0.000000]\n"
" - Link [15]\n"
" - Name: right_wheel\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [2.000000]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [2.000000]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.145833 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.145833 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.125000]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.554282 | -0.625029 | -0.025000]\n"
" [-1.570700 | 0.000000 | 0.000000]\n"
" - Link [18]\n"
" - Name: caster\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [1.000000]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [1.000000]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.100000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.100000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.100000]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [-0.957138 | 0.000000 | -0.125000]\n"
" [0.000000 | 0.000000 | 0.000000]\n";
EXPECT_EQ(expectedOutput, output);
Expand All @@ -267,12 +296,14 @@ TEST(ModelCommandAPI, Commands)
" - Link [18]\n"
" - Name: caster\n"
" - Parent: vehicle_blue [8]\n"
" - Mass: [1.000000]\n"
" - Inertial Matrix: \n"
" - Mass (kg): [1.000000]\n"
" - Inertial Pose:\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Inertial Matrix (kg⋅m^2): \n"
" [0.100000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.100000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.100000]\n"
" - Pose: \n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [-0.957138 | 0.000000 | -0.125000]\n"
" [0.000000 | 0.000000 | 0.000000]\n";
EXPECT_EQ(expectedOutput, output);
Expand All @@ -289,21 +320,34 @@ TEST(ModelCommandAPI, Commands)
" - Joint [21]\n"
" - Name: left_wheel_joint\n"
" - Parent: vehicle_blue [8]\n"
" - Joint type: revolute\n"
" - Parent Link: [left_wheel]\n"
" - Child Link: [chassis]\n"
" - Type: revolute\n"
" - Parent Link: left_wheel\n"
" - Child Link: chassis\n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Axis unit vector [ XYZ ]: \n"
" [0 | 0 | 1]\n"
" - Joint [22]\n"
" - Name: right_wheel_joint\n"
" - Parent: vehicle_blue [8]\n"
" - Joint type: revolute\n"
" - Parent Link: [right_wheel]\n"
" - Child Link: [chassis]\n"
" - Type: revolute\n"
" - Parent Link: right_wheel\n"
" - Child Link: chassis\n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.000000]\n"
" - Axis unit vector [ XYZ ]: \n"
" [0 | 0 | 1]\n"
" - Joint [23]\n"
" - Name: caster_wheel\n"
" - Parent: vehicle_blue [8]\n"
" - Joint type: ball\n"
" - Parent Link: [caster]\n"
" - Child Link: [chassis]\n";
" - Type: ball\n"
" - Parent Link: caster\n"
" - Child Link: chassis\n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.000000]\n";
EXPECT_EQ(expectedOutput, output);
}

Expand All @@ -318,9 +362,12 @@ TEST(ModelCommandAPI, Commands)
" - Joint [23]\n"
" - Name: caster_wheel\n"
" - Parent: vehicle_blue [8]\n"
" - Joint type: ball\n"
" - Parent Link: [caster]\n"
" - Child Link: [chassis]\n";
" - Type: ball\n"
" - Parent Link: caster\n"
" - Child Link: chassis\n"
" - Pose [ XYZ (m) ] [ RPY (rad) ]: \n"
" [0.000000 | 0.000000 | 0.000000]\n"
" [0.000000 | 0.000000 | 0.000000]\n";
EXPECT_EQ(expectedOutput, output);
}
}
Expand Down
Loading

0 comments on commit 55018ee

Please sign in to comment.