35 import roslib; roslib.load_manifest(
'calibration_estimation')
44 from sensor_msgs.msg
import JointState, CameraInfo
58 config_dict = yaml.load(config_yaml)
67 M_robot = RobotMeasurement()
68 M_robot.M_laser.append( LaserMeasurement(laser_id=
"laser1"))\
70 blocks = bundler.build_blocks(M_robot)
72 self.assertEqual( len(blocks), 1)
73 self.assertEqual( blocks[0]._M_laser.laser_id,
"laser1")
78 <link name="base_link"/> 79 <joint name="j0" type="fixed"> 80 <origin xyz="0 0 0" rpy="0 0 0"/> 81 <parent link="base_link"/> 82 <child link="j0_link"/> 84 <link name="j0_link"/> 85 <joint name="j1" type="revolute"> 87 <origin xyz="0 0 0" rpy="0 0 0"/> 88 <parent link="j0_link"/> 89 <child link="j1_link"/> 91 <link name="j1_link"/> 92 <joint name="j2" type="fixed"> 93 <origin xyz="0 0 0" rpy="0 0 0"/> 94 <parent link="j1_link"/> 95 <child link="j2_link"/> 97 <link name="j2_link"/> 100 config = yaml.load(
''' 118 return config[
"sensors"],
UrdfParams(urdf, config)
127 joint_points = [ JointState(position=[0,0,1]),
128 JointState(position=[pi/2,0,2]) ]
130 sensor =
TiltingLaserSensor(config[
"tilting_lasers"][
"laserA"], LaserMeasurement(laser_id=
"laserA",
131 joint_points=joint_points))
133 sensor.update_config(robot_params)
135 cov = sensor.compute_cov(
None)
140 self.assertAlmostEqual(cov[0,0], 1.0, 6)
141 self.assertAlmostEqual(cov[1,1], 1.0, 6)
142 self.assertAlmostEqual(cov[2,2], 1.0, 6)
143 self.assertAlmostEqual(cov[3,3], 4.0, 6)
144 self.assertAlmostEqual(cov[4,4], 4.0, 6)
145 self.assertAlmostEqual(cov[5,5], 1.0, 6)
151 joint_points = [ JointState(position=[0,0,1]),
152 JointState(position=[pi/2,0,2]) ]
154 sensor =
TiltingLaserSensor(config[
"tilting_lasers"][
"laserA"], LaserMeasurement(laser_id=
"laserA",
155 joint_points=joint_points))
157 sensor.update_config(robot_params)
158 gamma = sensor.compute_marginal_gamma_sqrt(
None)
162 self.assertAlmostEqual(gamma[0,0], 1.0, 6)
163 self.assertAlmostEqual(gamma[1,1], 1.0, 6)
164 self.assertAlmostEqual(gamma[2,2], 1.0, 6)
165 self.assertAlmostEqual(gamma[3,3], 0.5, 6)
166 self.assertAlmostEqual(gamma[4,4], 0.5, 6)
167 self.assertAlmostEqual(gamma[5,5], 1.0, 6)
173 joint_points = [ JointState(position=[0,0,0]),
174 JointState(position=[0,pi/2,1]),
175 JointState(position=[pi/2,0,1]) ]
177 sensor =
TiltingLaserSensor(config[
"tilting_lasers"][
"laserA"], LaserMeasurement(laser_id=
"laserA",
178 joint_points=joint_points))
180 sensor.update_config(robot_params)
182 target_pts = matrix( [ [ 0, 0, 0 ],
187 h = sensor.compute_expected(target_pts)
188 z = sensor.get_measurement()
189 r = sensor.compute_residual(target_pts)
191 self.assertAlmostEqual(numpy.linalg.norm(h-target_pts), 0.0, 6)
192 self.assertAlmostEqual(numpy.linalg.norm(z-target_pts), 0.0, 6)
193 self.assertAlmostEqual(numpy.linalg.norm(r), 0.0, 6)
196 sparsity = sensor.build_sparsity_dict()
197 self.assertEqual(sparsity[
'transforms'][
'j0'], [1,1,1,1,1,1])
198 self.assertEqual(sparsity[
'transforms'][
'j1'], [1,1,1,1,1,1])
199 self.assertEqual(sparsity[
'transforms'][
'j2'], [1,1,1,1,1,1])
200 self.assertEqual(sparsity[
'tilting_lasers'][
'laserA'][
'gearing'], 1)
203 if __name__ ==
'__main__':
205 rostest.unitrun(
'calibration_estimation',
'test_TiltingLaserBundler', TestTiltingLaserBundler, coverage_packages=[
'calibration_estimation.sensors.tilting_laser_sensor'])
206 rostest.unitrun(
'calibration_estimation',
'test_TiltingLaser', TestTiltingLaser, coverage_packages=[
'calibration_estimation.sensors.tilting_laser_sensor'])
def test_tilting_laser_1(self)