Skip to content

Commit 2cecaf8

Browse files
committed
test: improve mujoco_ros_sensors coverage
1 parent 6529e8c commit 2cecaf8

File tree

3 files changed

+80
-5
lines changed

3 files changed

+80
-5
lines changed

CHANGELOG.md

+1
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ Loading and reset times are reported in the server debug log. All plugin stats c
1616

1717
### Changed
1818
* Moved `mujoco_ros::Viewer::Clock` definition to `mujoco_ros::Clock` (into common_types.h).
19+
* Increased test coverage of `mujoco_ros_sensors` plugin.
1920

2021
Contributors: @DavidPL1
2122

mujoco_ros_sensors/test/mujoco_sensors_test.cpp

+74-3
Original file line numberDiff line numberDiff line change
@@ -303,9 +303,11 @@ TEST_F(TrainEnvFixture, Sensor3DOF)
303303
mujoco_ros_msgs::SensorNoiseModel noise_model;
304304
noise_model.mean.emplace_back(0.0);
305305
noise_model.mean.emplace_back(1.0);
306+
noise_model.mean.emplace_back(0.0);
306307
noise_model.std.emplace_back(0.025);
307308
noise_model.std.emplace_back(0.0);
308-
noise_model.set_flag = 3;
309+
noise_model.std.emplace_back(0.0);
310+
noise_model.set_flag = 7;
309311
noise_model.sensor_name = "vel_EE";
310312

311313
mujoco_ros_msgs::RegisterSensorNoiseModels srv;
@@ -416,9 +418,11 @@ TEST_F(TrainEnvFixture, Framepos)
416418
mujoco_ros_msgs::SensorNoiseModel noise_model;
417419
noise_model.mean.emplace_back(0.0);
418420
noise_model.mean.emplace_back(1.0);
421+
noise_model.mean.emplace_back(0.0);
419422
noise_model.std.emplace_back(0.025);
420423
noise_model.std.emplace_back(0.0);
421-
noise_model.set_flag = 3;
424+
noise_model.std.emplace_back(0.0);
425+
noise_model.set_flag = 7;
422426
noise_model.sensor_name = "immovable_pos";
423427

424428
mujoco_ros_msgs::RegisterSensorNoiseModels srv;
@@ -608,9 +612,13 @@ TEST_F(TrainEnvFixture, quaternion)
608612
{ msgPtr->quaternion.w, msgPtr->quaternion.x, msgPtr->quaternion.y, msgPtr->quaternion.z }, 0.0001, true);
609613

610614
mujoco_ros_msgs::SensorNoiseModel noise_model;
615+
noise_model.mean.emplace_back(0.0);
616+
noise_model.mean.emplace_back(0.0);
611617
noise_model.mean.emplace_back(1.0);
618+
noise_model.std.emplace_back(0.0);
619+
noise_model.std.emplace_back(0.0);
612620
noise_model.std.emplace_back(0.025);
613-
noise_model.set_flag = 4;
621+
noise_model.set_flag = 7;
614622
noise_model.sensor_name = "immovable_quat";
615623

616624
mujoco_ros_msgs::RegisterSensorNoiseModels srv;
@@ -710,3 +718,66 @@ TEST_F(TrainEnvFixture, quaternion)
710718
EXPECT_EQ(variances[4], 0);
711719
EXPECT_EQ(variances[5], 0);
712720
}
721+
722+
TEST_F(EvalEnvFixture, NoAdmEvalNoiseModelChange)
723+
{
724+
mujoco_ros_msgs::SensorNoiseModel noise_model;
725+
noise_model.mean.emplace_back(0.0);
726+
noise_model.mean.emplace_back(1.0);
727+
noise_model.std.emplace_back(0.025);
728+
noise_model.std.emplace_back(0.0);
729+
noise_model.set_flag = 3;
730+
noise_model.sensor_name = "vel_EE";
731+
732+
mujoco_ros_msgs::RegisterSensorNoiseModels srv;
733+
srv.request.noise_models.emplace_back(noise_model);
734+
srv.request.admin_hash = "some_wrong_hash";
735+
736+
ros::ServiceClient client =
737+
nh->serviceClient<mujoco_ros_msgs::RegisterSensorNoiseModels>("/sensors/register_noise_models");
738+
EXPECT_TRUE(client.call(srv)) << "Service call failed!";
739+
740+
EXPECT_EQ(srv.response.success, false) << "Service call should have failed!";
741+
}
742+
743+
TEST_F(EvalEnvFixture, AllowedEvalNoiseModelChange)
744+
{
745+
mujoco_ros_msgs::SensorNoiseModel noise_model;
746+
noise_model.mean.emplace_back(0.0);
747+
noise_model.mean.emplace_back(1.0);
748+
noise_model.std.emplace_back(0.025);
749+
noise_model.std.emplace_back(0.0);
750+
noise_model.set_flag = 3;
751+
noise_model.sensor_name = "vel_EE";
752+
753+
mujoco_ros_msgs::RegisterSensorNoiseModels srv;
754+
srv.request.noise_models.emplace_back(noise_model);
755+
srv.request.admin_hash = "some_hash";
756+
757+
ros::ServiceClient client =
758+
nh->serviceClient<mujoco_ros_msgs::RegisterSensorNoiseModels>("/sensors/register_noise_models");
759+
EXPECT_TRUE(client.call(srv)) << "Service call failed!";
760+
761+
EXPECT_EQ(srv.response.success, true) << "Service call should have succeeded!";
762+
}
763+
764+
TEST_F(TrainEnvFixture, UnknownSensorAddNoise)
765+
{
766+
mujoco_ros_msgs::SensorNoiseModel noise_model;
767+
noise_model.mean.emplace_back(0.0);
768+
noise_model.mean.emplace_back(1.0);
769+
noise_model.std.emplace_back(0.025);
770+
noise_model.std.emplace_back(0.0);
771+
noise_model.set_flag = 3;
772+
noise_model.sensor_name = "unknown_sensor";
773+
774+
mujoco_ros_msgs::RegisterSensorNoiseModels srv;
775+
srv.request.noise_models.emplace_back(noise_model);
776+
srv.request.admin_hash = "example_hash";
777+
778+
ros::ServiceClient client =
779+
nh->serviceClient<mujoco_ros_msgs::RegisterSensorNoiseModels>("/sensors/register_noise_models");
780+
EXPECT_TRUE(client.call(srv)) << "Service call failed!";
781+
782+
EXPECT_EQ(srv.response.success, true) << "Service call should have succeeded!";
783+
}

mujoco_ros_sensors/test/sensors_world.xml

+5-2
Original file line numberDiff line numberDiff line change
@@ -40,10 +40,13 @@
4040
</worldbody>
4141

4242
<sensor>
43-
<framepos name="immovable_pos" objtype="xbody" objname="immovable" />
44-
<framequat name="immovable_quat" objtype="xbody" objname="immovable" />
43+
<framepos name="immovable_pos" objtype="xbody" objname="immovable" />
44+
<framequat name="immovable_quat" objtype="xbody" objname="immovable" />
45+
<framexaxis name="framex_EE" objtype="site" objname="joint2_site" />
4546

4647
<velocimeter name="vel_EE" site="joint2_site" />
4748
<jointvel name="vel_joint2" joint="joint2" />
49+
50+
<subtreecom name="subtree_end_link" body="end_link" />
4851
</sensor>
4952
</mujoco>

0 commit comments

Comments
 (0)