Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include <urdf/model.h>
00018 #include <robot_calibration/ceres/optimizer.h>
00019 #include <gtest/gtest.h>
00020
00021 std::string robot_description =
00022 "<?xml version='1.0' ?>"
00023 "<robot name='maxwell'>"
00024 " <link name='base_link'/>"
00025 " <joint name='torso_joint' type='fixed'>"
00026 " <origin rpy='0 0 0' xyz='-0.00635 0 0.7914'/>"
00027 " <parent link='base_link'/>"
00028 " <child link='torso_link'/>"
00029 " </joint>"
00030 " <link name='torso_link'/>"
00031 " <joint name='torso_actuator_joint' type='fixed'>"
00032 " <origin rpy='0 0 0' xyz='0 0 0'/>"
00033 " <parent link='torso_link'/>"
00034 " <child link='torso_actuator_link'/>"
00035 " </joint>"
00036 " <link name='torso_actuator_link'/>"
00037 " <joint name='arm_lift_joint' type='prismatic'>"
00038 " <axis xyz='0 0 1'/>"
00039 " <limit effort='30' lower='-0.464' upper='0' velocity='0.0508'/>"
00040 " <origin rpy='0 0 0' xyz='0 0 0'/>"
00041 " <parent link='torso_link'/>"
00042 " <child link='arm_lift_link'/>"
00043 " </joint>"
00044 " <link name='arm_lift_link'/>"
00045 " <joint name='arm_base_joint' type='fixed'>"
00046 " <origin rpy='0 0 0' xyz='0.0611 0 0'/>"
00047 " <parent link='arm_lift_link'/>"
00048 " <child link='arm_link'/>"
00049 " </joint>"
00050 " <link name='arm_link'/>"
00051 " <joint name='arm_shoulder_pan_servo_joint' type='fixed'>"
00052 " <origin rpy='0 0 0' xyz='0 0 0'/>"
00053 " <parent link='arm_link'/>"
00054 " <child link='arm_shoulder_pan_servo_link'/>"
00055 " </joint>"
00056 " <link name='arm_shoulder_pan_servo_link'/>"
00057 " <joint name='arm_shoulder_pan_joint' type='revolute'>"
00058 " <origin rpy='0 0 0' xyz='0 0 0.0235'/>"
00059 " <axis xyz='0 0 1'/>"
00060 " <limit effort='30' lower='-1.57' upper='1.57' velocity='0.524'/>"
00061 " <parent link='arm_shoulder_pan_servo_link'/>"
00062 " <child link='arm_shoulder_pan_link'/>"
00063 " </joint>"
00064 " <link name='arm_shoulder_pan_link'/>"
00065 " <joint name='arm_shoulder_lift_servo_joint' type='fixed'>"
00066 " <origin rpy='0 -1.57 0' xyz='0 0 0.0526'/>"
00067 " <parent link='arm_shoulder_pan_link'/>"
00068 " <child link='arm_shoulder_lift_servo_link'/>"
00069 " </joint>"
00070 " <link name='arm_shoulder_lift_servo_link'/>"
00071 " <joint name='arm_shoulder_lift_joint' type='revolute'>"
00072 " <origin rpy='0 1.57 0' xyz='0 0 0'/>"
00073 " <axis xyz='0 1 0'/>"
00074 " <limit effort='30' lower='-1.77' upper='1.317' velocity='0.524'/>"
00075 " <parent link='arm_shoulder_lift_servo_link'/>"
00076 " <child link='arm_shoulder_lift_link'/>"
00077 " </joint>"
00078 " <link name='arm_shoulder_lift_link'/>"
00079 " <joint name='arm_upperarm_roll_servo_joint' type='fixed'>"
00080 " <origin rpy='1.57 1.57 0' xyz='0.0712978 0 0'/>"
00081 " <parent link='arm_shoulder_lift_link'/>"
00082 " <child link='arm_upperarm_roll_servo_link'/>"
00083 " </joint>"
00084 " <link name='arm_upperarm_roll_servo_link'/>"
00085 " <joint name='arm_upperarm_roll_joint' type='revolute'>"
00086 " <origin rpy='-1.57 0 1.57' xyz='0 0 0'/>"
00087 " <axis xyz='1 0 0'/>"
00088 " <limit effort='30' lower='-2' upper='2' velocity='0.524'/>"
00089 " <parent link='arm_upperarm_roll_servo_link'/>"
00090 " <child link='arm_upperarm_roll_link'/>"
00091 " </joint>"
00092 " <link name='arm_upperarm_roll_link'/>"
00093 " <joint name='arm_elbow_flex_joint' type='revolute'>"
00094 " <origin rpy='0 0 0' xyz='0.0869955 0 0'/>"
00095 " <axis xyz='0 1 0'/>"
00096 " <limit effort='30' lower='-1.57' upper='2.617' velocity='0.524'/>"
00097 " <parent link='arm_upperarm_roll_link'/>"
00098 " <child link='arm_elbow_flex_link'/>"
00099 " </joint>"
00100 " <link name='arm_elbow_flex_link'/>"
00101 " <joint name='arm_forearm_fixed_joint' type='fixed'>"
00102 " <origin rpy='0 0 0' xyz='0 0 0'/>"
00103 " <parent link='arm_elbow_flex_link'/>"
00104 " <child link='arm_forearm_link'/>"
00105 " </joint>"
00106 " <link name='arm_forearm_link'/>"
00107 " <joint name='arm_wrist_flex_servo_joint' type='fixed'>"
00108 " <origin rpy='0 0 0' xyz='0.125 0 0'/>"
00109 " <parent link='arm_forearm_link'/>"
00110 " <child link='arm_wrist_flex_servo_link'/>"
00111 " </joint>"
00112 " <link name='arm_wrist_flex_servo_link'/>"
00113 " <joint name='arm_wrist_flex_joint' type='revolute'>"
00114 " <origin rpy='0 0 0' xyz='0 0 0.0'/>"
00115 " <axis xyz='0 1 0'/>"
00116 " <limit effort='30' lower='-1.57' upper='1.57' velocity='0.785'/>"
00117 " <parent link='arm_wrist_flex_servo_link'/>"
00118 " <child link='arm_wrist_flex_link'/>"
00119 " </joint>"
00120 " <link name='arm_wrist_flex_link'/>"
00121 " <joint name='arm_wrist_roll_joint' type='revolute'>"
00122 " <axis xyz='1 0 0'/>"
00123 " <limit effort='30' lower='-2.617' upper='2.617' velocity='0.785'/>"
00124 " <origin rpy='0 0 0' xyz='0.031 0 0'/>"
00125 " <parent link='arm_wrist_flex_link'/>"
00126 " <child link='arm_wrist_roll_link'/>"
00127 " </joint>"
00128 " <link name='arm_wrist_roll_link'/>"
00129 " <joint name='gripper_joint' type='fixed'>"
00130 " <axis xyz='0 0 1'/>"
00131 " <origin rpy='0 0 0' xyz='0.15 0 -0.015'/>"
00132 " <parent link='arm_wrist_roll_link'/>"
00133 " <child link='gripper_led_frame'/>"
00134 " </joint>"
00135 " <link name='gripper_led_frame'/>"
00136 " <joint name='head_joint' type='fixed'>"
00137 " <origin rpy='0 0 0' xyz='0 0 0.512375'/>"
00138 " <parent link='torso_link'/>"
00139 " <child link='head_link'/>"
00140 " </joint>"
00141 " <link name='head_link'/>"
00142 " <joint name='head_pan_servo_joint' type='fixed'>"
00143 " <origin rpy='0 0 0' xyz='0.010 0 0.0254'/>"
00144 " <parent link='head_link'/>"
00145 " <child link='head_pan_servo_link'/>"
00146 " </joint>"
00147 " <link name='head_pan_servo_link'/>"
00148 " <joint name='head_pan_joint' type='revolute'>"
00149 " <origin rpy='0 0 0' xyz='0 0 0.019'/>"
00150 " <axis xyz='0 0 1'/>"
00151 " <limit effort='30' lower='-2.617' upper='2.617' velocity='1.0'/>"
00152 " <parent link='head_pan_servo_link'/>"
00153 " <child link='head_pan_link'/>"
00154 " </joint>"
00155 " <link name='head_pan_link'/>"
00156 " <joint name='head_tilt_servo_joint' type='fixed'>"
00157 " <origin rpy='0 0 0' xyz='0 0 0.0415'/>"
00158 " <parent link='head_pan_link'/>"
00159 " <child link='head_tilt_servo_link'/>"
00160 " </joint>"
00161 " <link name='head_tilt_servo_link'/>"
00162 " <joint name='head_tilt_joint' type='revolute'>"
00163 " <origin rpy='0 0 0' xyz='0 0 0'/>"
00164 " <axis xyz='0 1 0'/>"
00165 " <limit effort='30' lower='-1.57' upper='1.57' velocity='1.0'/>"
00166 " <parent link='head_tilt_servo_link'/>"
00167 " <child link='head_tilt_link'/>"
00168 " </joint>"
00169 " <link name='head_tilt_link'/>"
00170 " <joint name='head_camera_frame_joint' type='fixed'>"
00171 " <origin rpy='0 0 0' xyz='0 0 0.026'/>"
00172 " <parent link='head_tilt_link'/>"
00173 " <child link='head_camera_frame'/>"
00174 " </joint>"
00175 " <link name='head_camera_frame'/>"
00176 " <joint name='head_camera_ir_joint' type='fixed'>"
00177 " <origin rpy='0 0 0' xyz='0.01905 -0.0269875 0.032075'/>"
00178 " <parent link='head_camera_frame'/>"
00179 " <child link='head_camera_ir_link'/>"
00180 " </joint>"
00181 " <link name='head_camera_ir_link'/>"
00182 " <joint name='head_camera_ir_optical_frame_joint' type='fixed'>"
00183 " <origin rpy='-1.57 0.0 -1.57' xyz='0 0 0'/>"
00184 " <parent link='head_camera_ir_link'/>"
00185 " <child link='head_camera_ir_optical_frame'/>"
00186 " </joint>"
00187 " <link name='head_camera_ir_optical_frame'/>"
00188 " <joint name='head_camera_rgb_joint' type='fixed'>"
00189 " <origin rpy='0 -0.08 0' xyz='0 0.0552875 0'/>"
00190 " <parent link='head_camera_ir_link'/>"
00191 " <child link='head_camera_rgb_link'/>"
00192 " </joint>"
00193 " <link name='head_camera_rgb_link'/>"
00194 " <joint name='head_camera_rgb_optical_frame_joint' type='fixed'>"
00195 " <origin rpy='-1.57 0.0 -1.57' xyz='0 0 0'/>"
00196 " <parent link='head_camera_rgb_link'/>"
00197 " <child link='head_camera_rgb_optical_frame'/>"
00198 " </joint>"
00199 " <link name='head_camera_rgb_optical_frame'/>"
00200 "</robot>";
00201
00202 TEST(ErrorBlockTests, error_blocks_maxwell)
00203 {
00204 ros::NodeHandle nh("~");
00205
00206 robot_calibration::Optimizer opt(robot_description);
00207
00208 std::vector<robot_calibration_msgs::CalibrationData> data;
00209 robot_calibration_msgs::CalibrationData msg;
00210
00211
00212 msg.joint_states.name.resize(10);
00213 msg.joint_states.name[0] = "arm_lift_flex_joint";
00214 msg.joint_states.name[1] = "arm_shoulder_pan_joint";
00215 msg.joint_states.name[2] = "arm_shoulder_lift_joint";
00216 msg.joint_states.name[3] = "arm_upperarm_roll_joint";
00217 msg.joint_states.name[4] = "arm_elbow_flex_joint";
00218 msg.joint_states.name[5] = "arm_wrist_flex_joint";
00219 msg.joint_states.name[6] = "arm_wrist_roll_joint";
00220 msg.joint_states.name[7] = "head_pan_joint";
00221 msg.joint_states.name[8] = "head_tilt_joint";
00222 msg.joint_states.name[9] = "arm_lift_joint";
00223 msg.joint_states.position.resize(10);
00224 msg.joint_states.position[0] = 0.0;
00225 msg.joint_states.position[1] = -0.814830;
00226 msg.joint_states.position[2] = -0.00022290000000002586;
00227 msg.joint_states.position[3] = 0.0;
00228 msg.joint_states.position[4] = -0.7087341;
00229 msg.joint_states.position[5] = 0.0;
00230 msg.joint_states.position[6] = 0.0;
00231 msg.joint_states.position[7] = -0.8280187999999999;
00232 msg.joint_states.position[8] = 0.6358500000000002;
00233 msg.joint_states.position[9] = 0.0;
00234
00235
00236 msg.observations.resize(2);
00237 msg.observations[0].sensor_name = "camera";
00238 msg.observations[1].sensor_name = "arm";
00239
00240 msg.observations[0].features.resize(1);
00241 msg.observations[0].features[0].header.frame_id = "head_camera_rgb_optical_frame";
00242 msg.observations[0].features[0].point.x = -0.0143163670728;
00243 msg.observations[0].features[0].point.y = 0.111304592065;
00244 msg.observations[0].features[0].point.z = 0.522079317365;
00245
00246 msg.observations[0].ext_camera_info.camera_info.P[0] = 100.0;
00247 msg.observations[0].ext_camera_info.camera_info.P[5] = 100.0;
00248 msg.observations[0].ext_camera_info.camera_info.P[2] = 320.0;
00249 msg.observations[0].ext_camera_info.camera_info.P[6] = 240.0;
00250 msg.observations[0].ext_camera_info.parameters.resize(2);
00251 msg.observations[0].ext_camera_info.parameters[0].name = "z_offset";
00252 msg.observations[0].ext_camera_info.parameters[0].value = 0.0;
00253 msg.observations[0].ext_camera_info.parameters[1].name = "z_scaling";
00254 msg.observations[0].ext_camera_info.parameters[1].value = 1.0;
00255
00256 msg.observations[1].features.resize(1);
00257 msg.observations[1].features[0].header.frame_id = "gripper_led_frame";
00258 msg.observations[1].features[0].point.x = 0.0;
00259 msg.observations[1].features[0].point.y = 0.0;
00260 msg.observations[1].features[0].point.z = 0.0;
00261
00262
00263 data.push_back(msg);
00264
00265
00266 msg.joint_states.position[1] = -0.019781999999999966;
00267 msg.joint_states.position[7] = 0.0;
00268 msg.observations[0].features[0].point.x = 0.0365330705881;
00269 msg.observations[0].features[0].point.y = 0.102609552493;
00270 msg.observations[0].features[0].point.z = 0.536061220027;
00271 data.push_back(msg);
00272
00273
00274 msg.joint_states.position[1] = 0.883596;
00275 msg.joint_states.position[7] = 0.9442135999999999;
00276 msg.observations[0].features[0].point.x = 0.0942445346646;
00277 msg.observations[0].features[0].point.y = 0.11409172323;
00278 msg.observations[0].features[0].point.z = 0.517497963716;
00279 data.push_back(msg);
00280
00281
00282 robot_calibration::OptimizationParams params;
00283 params.LoadFromROS(nh);
00284
00285
00286 opt.optimize(params, data, false);
00287 EXPECT_LT(opt.summary()->initial_cost, 1e-20);
00288 }
00289
00290 int main(int argc, char** argv)
00291 {
00292 ros::init(argc, argv, "error_block_tests");
00293 testing::InitGoogleTest(&argc, argv);
00294 return RUN_ALL_TESTS();
00295 }