<> <> This package uses the [[ar_kinect|ar_kinect]] module to calibrate a fixed joint between the base link and a Kinect camera which monitors a Katana arm equipped with an AR code. Make sure to merge the latest [[http://kos.informatik.uos.de/uos-public-fuerte.rosinstall|uos-public-fuerte.rosinstall]] to get the correct [[ar_kinect]] and [[ccny_vision]] stacks. == Tutorial == First of all you need to attach an AR code to the arm. The trajectory of the calibration was choosen to expose the front side of `katana_motor4_lift_joint` best. {{attachment:ar_marker_on_katana.jpg}} If you want to use the standard setup, you can print the AR code from data/4x4_9.ps at 42mm side length and stick it to the proper place. Here comes the tricky part... You need to provide a transform between `/base_link` and the center of the pattern, which is expected to be called `/kinect_pattern`. This could look ''something'' like: {{{ rosrun tf static_transform_publisher .075 -.035 0.000 .151 1.571 -1.571 /katana_motor4_lift_link /katana_pattern 100 }}} You can also just include it with the rest of your robots urdf description. Now, fire up your usual setup including the [[openni_kinect|kinect node]] and the [[katana|katana driver]]. Make sure all reachable positions in front of the katana arm can be seen by the Kinect and '''''move all possible obstacles out of the way! The arm will not perform any kind of obstacle avoidance and will move through most of the reachable space during calibration.''''' Now, you can simply run the following to calibrate: {{{ roslaunch katana_kinect_calibration calibrate.launch }}} If you want to monitor the calibration procedure in [[rviz|rviz]], make sure your `kinect_link` frame is not connected to the rest of your robot's tf tree and add `publish_tf:=true` to the above. This will show you the averaged position of the Kinect w.r.t. your robot for each pose independently. The calibration will move the arm through 6 poses and the module will try to detect the AR marker a sufficient number of times. '''If the calibration does not find the pattern often enough (or not at all), make sure illumination is not too bright and if possible indirect!'''(shading the pattern with your hand might even help...) When finished, the arm will move to the old pose and a config file is written to `$HOME/.ros/kinect_pose.urdf.xacro`. This can be used in a robot description to glue the Kinect to the base link using e.g. {{{ }}} The launch file also provides all other parameters of the configure.py node as args, so you can influence the whole procedure quite a bit. == ROS API == This package provides only one node `calibrate.py` which will perform the actual calibration procedure, write the calibrated parameters and terminate. {{{ #!clearsilver CS/NodeAPI name = calibrate.py desc = performs calibration of kinect pose using katana param { 0.name = ~samples_required 0.type = int 0.default = 300 0.desc = How many samples should be collected in each pose 1.name = ~timeout 1.type = int 1.default = 20 1.desc = How many seconds should we wait for the samples 2.name = ~runs 2.type = int 2.default = 1 2.desc = How many times should all poses be measured 3.name = ~config_file 3.type = string 3.default = $HOME/.ros/kinect_pose.urdf.xacro 3.desc = Where to write the final configuration to 4.name = ~write_config 4.type = bool 4.default = true 4.desc = Should we (over?)write the config file 5.name = ~publish_tf 5.type = bool 5.default = false 5.desc = Should we publish the transform we currently averaged } sub { 0.name = /katana_joint_states 0.type = sensor_msgs/JointState 0.desc = needed to restore the old pose after the calibration 1.name = /ar_pose_markers 1.type = ar_pose/ARMarkers 1.desc = publishes the recognized AR codes } srv_called { 0.name = katana_arm_controller/joint_movement_action 0.type = katana_msgs/JointMovementAction 0.desc = move the arm to a specific JointState } req_tf { 0.from = /katana_pattern 0.to = /base_link 0.desc = (most likely transitive) transform that fixes the AR pattern } prov_tf { 0.from = /kinect_link 0.to = /base_link 0.desc = optionally monitor calibration using publish_tf:=true } }}}