|
From: <jfa...@us...> - 2009-01-17 08:10:22
|
Revision: 9626
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=9626&view=rev
Author: jfaustwg
Date: 2009-01-17 08:10:01 +0000 (Sat, 17 Jan 2009)
Log Message:
-----------
roscpp API changes
* ros::node -> ros::Node
* ros::msg -> ros::Message
* deprecated methods removed
* rosconsole/rosconsole.h -> ros/console.h
* goodbye rosthread
Modified Paths:
--------------
pkg/trunk/audio/audio_capture/audio_capture.cpp
pkg/trunk/audio/audio_capture/audio_clip_writer.cpp
pkg/trunk/calibration/kinematic_calibration/manifest.xml
pkg/trunk/calibration/kinematic_calibration/src/arm_phasespace_grabber.cpp
pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp
pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml
pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp
pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h
pkg/trunk/controllers/control_toolbox/src/serialchain_model.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_dynamics_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_position_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_velocity_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_position_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/grasp_point_node.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_arm_dynamics_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_dynamics_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_velocity_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/grasp_point_node.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_qualification.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_velocity_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_arm_dynamics_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_service.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_grasp_point_node.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/sine_sweep_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/src/backlash_controller.cpp
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/src/hysteresis_controller.cpp
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/src/sine_sweep_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_effort_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_pd_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_smoothing_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_effort_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_torque_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_velocity_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_pose_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_twist_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_wrench_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_autotuner.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_blind_calibration_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_effort_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_pd_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_smoothing_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/lqr_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/ros_serialchain_model.cpp
pkg/trunk/deprecated/dc1394_cam/manifest.xml
pkg/trunk/deprecated/dc1394_cam_server/src/check_params/check_params.cpp
pkg/trunk/deprecated/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp
pkg/trunk/deprecated/plan_kinematic_path/src/plan_kinematic_path.cpp
pkg/trunk/deprecated/ransac_ground_plane_extraction/include/ransac_ground_plane_extraction/ransac_ground_plane_extraction_node.h
pkg/trunk/deprecated/ransac_ground_plane_extraction/src/ransac_ground_plane_extraction_node.cpp
pkg/trunk/deprecated/resource_locator/src/reslocator.cpp
pkg/trunk/deprecated/scan_utils/include/listen_node/scanListenNode.h
pkg/trunk/deprecated/scan_utils/src/cloudToOctree/cloudToOctree.cpp
pkg/trunk/deprecated/scan_utils/src/listen_node/scanListenNode.cpp
pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
pkg/trunk/drivers/cam/axis_cam/src/axis_demo/axis_demo.cpp
pkg/trunk/drivers/cam/axis_cam/src/axis_ptz/axis_ptz.cpp
pkg/trunk/drivers/cam/bumblebee_bridge/bumblebee_bridge.cpp
pkg/trunk/drivers/cam/dcam/src/nodes/check_params.cpp
pkg/trunk/drivers/cam/dcam/src/nodes/dcam.cpp
pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp
pkg/trunk/drivers/cam/elphel_cam/src/elphel_node/elphel_node.cpp
pkg/trunk/drivers/imu/imu_node/imu_node.cc
pkg/trunk/drivers/input/joy/joy.cpp
pkg/trunk/drivers/input/joy_node/joy_node.cpp
pkg/trunk/drivers/input/joy_view/joy_view.cpp
pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp
pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp
pkg/trunk/drivers/laser/laser_view/laser_view.cpp
pkg/trunk/drivers/laser/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp
pkg/trunk/drivers/motor/ethercat_hardware/src/ek1122.cpp
pkg/trunk/drivers/motor/ethercat_hardware/src/wg014.cpp
pkg/trunk/drivers/phase_space/phase_space_node.cpp
pkg/trunk/drivers/phase_space/phase_space_node.h
pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
pkg/trunk/drivers/robot/irobot_create/include/irobot_create/irobot_create.h
pkg/trunk/drivers/robot/irobot_create/irobot_create.cpp
pkg/trunk/drivers/robot/katana/libkatana/katana.cpp
pkg/trunk/drivers/robot/katana/nodes/katana_client/katana_client.cpp
pkg/trunk/drivers/robot/katana/nodes/katana_server/katana_server.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/include/point_cloud_assembler/base_assembler_srv.h
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/grab_cloud_data.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_snapshotter.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/test/test_assembler.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_odometry.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp
pkg/trunk/drivers/robot/pr2/pr2_power_board/include/power_node.h
pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node.cpp
pkg/trunk/drivers/robot/segway_apox/manifest.xml
pkg/trunk/drivers/robot/segway_apox/segway.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_mechanism_control.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_block_laser.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_bumper.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_camera.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_f3d.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_p3d.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_ptz.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_stereo_camera.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_time.h
pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_battery.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_mechanism_control.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_block_laser.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_bumper.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_camera.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_f3d.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_ptz.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_time.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.h
pkg/trunk/estimation/robot_pose_ekf/test/test_ekf.cpp
pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h
pkg/trunk/hardware_test/self_test/include/self_test/self_test.h
pkg/trunk/hardware_test/self_test/manifest.xml
pkg/trunk/hardware_test/self_test/src/run_selftest.cpp
pkg/trunk/hardware_test/self_test/src/selftest_example.cpp
pkg/trunk/highlevel/executive_python/manifest.xml
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/Executive.hh
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/EndEffectorStateAdapter.cc
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/Executive.cc
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/WatchDog.cc
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/trex_watchdog.cc
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp
pkg/trunk/highlevel/highlevel_controllers/include/HighlevelController.hh
pkg/trunk/highlevel/highlevel_controllers/include/IndefiniteNav.hh
pkg/trunk/highlevel/highlevel_controllers/src/ControlCli.cpp
pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
pkg/trunk/highlevel/highlevel_controllers/src/indefinite_nav.cpp
pkg/trunk/highlevel/highlevel_controllers/src/joy_batt_sender.cpp
pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp
pkg/trunk/manip/arm_trajectory/arm_trajectory.cc
pkg/trunk/manip/spacenav_node/src/spacenav_node.cpp
pkg/trunk/manip/teleop_arm_keyboard/teleop_arm_keyboard.cc
pkg/trunk/mapping/cloud_io/src/tools/bag_pcd.cpp
pkg/trunk/mapping/cloud_io/src/tools/pcd_generator.cpp
pkg/trunk/mapping/collision_map/src/collision_map.cpp
pkg/trunk/mapping/normal_estimation/src/normal_estimation.cpp
pkg/trunk/mapping/normal_estimation/src/normal_estimation_omp.cpp
pkg/trunk/mapping/planar_patch_map/src/planar_patch_map.cpp
pkg/trunk/mapping/planar_patch_map/src/planar_patch_map_omp.cpp
pkg/trunk/mapping/point_cloud_downsampler/src/cloud_downsampler.cpp
pkg/trunk/mapping/sample_consensus/src/tools/sac_ground_removal.cpp
pkg/trunk/mapping/semantic_point_annotator/src/semantic_point_annotator.cpp
pkg/trunk/mapping/semantic_point_annotator/src/semantic_point_annotator_omp.cpp
pkg/trunk/mapping/stereo_convex_patch_histogram/src/convex_patch_histogram.cpp
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
pkg/trunk/mechanism/mechanism_control/manifest.xml
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/mechanism/mechanism_control/test/ms_publisher_test.cpp
pkg/trunk/motion_planning/kinematic_planning/include/RKPConstraintEvaluator.h
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp
pkg/trunk/motion_planning/kinematic_planning/test/avoid_monster.cpp
pkg/trunk/motion_planning/navfn/src/navfn.cpp
pkg/trunk/motion_planning/planning_research/robarm3d/include/robarm3d/plan_path_node.h
pkg/trunk/motion_planning/planning_research/robarm3d/src/discrete_space_information/robarm/environment_robarm3d.cpp
pkg/trunk/motion_planning/planning_research/robarm3d/src/test/plan_path_node.cpp
pkg/trunk/motion_planning/planning_research/robarm3d/src/test/sim_grasp_path.cpp
pkg/trunk/motion_planning/planning_research/robarm3d/src/test/sim_path_srv.cpp
pkg/trunk/motion_planning/planning_research/robarm3d/src/test/simulate_arm_path.cpp
pkg/trunk/motion_planning/planning_research/robarm3d/src/test/test_forward_kinematics.cpp
pkg/trunk/motion_planning/planning_research/robarm3d/src/test/test_plan_path.cpp
pkg/trunk/motion_planning/test_collision_space/src/test_cs.cpp
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/amcl_player/cli.cpp
pkg/trunk/nav/deadreckon/deadreckon.cpp
pkg/trunk/nav/deadreckon/test_deadreckon_service.cpp
pkg/trunk/nav/fake_localization/fake_localization.cpp
pkg/trunk/nav/fake_localization/ground_truth_controller.cpp
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h
pkg/trunk/nav/nav_view/src/nav_view/tools.h
pkg/trunk/nav/nav_view/src/test/nav_view_test.cpp
pkg/trunk/nav/nav_view_sdl/nav_view.cpp
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.h
pkg/trunk/nav/slam_gmapping/src/tftest.cpp
pkg/trunk/nav/teleop_base/teleop_base.cpp
pkg/trunk/nav/teleop_base/teleop_head.cpp
pkg/trunk/nav/teleop_base_keyboard/teleop_base_keyboard.cc
pkg/trunk/nav/wavefront_player/cli.cpp
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp
pkg/trunk/openrave_planning/openraveros/src/session.h
pkg/trunk/openrave_planning/orrosplanning/src/collisionmapsystem.h
pkg/trunk/openrave_planning/orrosplanning/src/objecttransformsystem.h
pkg/trunk/openrave_planning/orrosplanning/src/plugindefs.h
pkg/trunk/openrave_planning/orrosplanning/src/rosrobotcontroller.h
pkg/trunk/openrave_planning/orrosplanning/src/rossensorsystem.h
pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp
pkg/trunk/simulators/rosstage/rosstage.cc
pkg/trunk/trajectory_rollout/include/trajectory_rollout/governor_node.h
pkg/trunk/trajectory_rollout/include/trajectory_rollout/trajectory_controller.h
pkg/trunk/trajectory_rollout/manifest.xml
pkg/trunk/trajectory_rollout/src/governor_node.cpp
pkg/trunk/unported/laser_viewer/src/laser_viewer/laser_viewer.cpp
pkg/trunk/unported/sharks/src/joyshark/joyshark.cpp
pkg/trunk/unported/simple_sdl_gui/src/key_monitor/key_monitor.cpp
pkg/trunk/unported/simple_sdl_gui/src/simple_sdl_gui_node/simple_sdl_gui.cpp
pkg/trunk/util/filter_coefficient_server/src/filter_coeff_client.cpp
pkg/trunk/util/filter_coefficient_server/test/check_function_calls.cpp
pkg/trunk/util/filter_demo/src/filtering_example.cpp
pkg/trunk/util/kinematics/libKinematics/include/libKinematics/pr2_ik_node.h
pkg/trunk/util/kinematics/libKinematics/src/pr2_ik_node.cpp
pkg/trunk/util/kinematics/robot_kinematics/test/robot_kinematics_test.cpp
pkg/trunk/util/laser_scan/include/laser_scan/median_filter.h
pkg/trunk/util/laser_scan/src/median_filter_node.cpp
pkg/trunk/util/laser_scan/src/scan_intensity_filter.cpp
pkg/trunk/util/laser_scan/src/scan_shadows_filter.cpp
pkg/trunk/util/logsetta/carmen/carmen_logger/carmen_logger.cpp
pkg/trunk/util/message_sequencing/example/testdelay.cpp
pkg/trunk/util/message_sequencing/example/testgen.cpp
pkg/trunk/util/message_sequencing/example/testrecv.cpp
pkg/trunk/util/message_sequencing/include/message_sequencing/time_sequencer.h
pkg/trunk/util/misc_utils/include/misc_utils/advertised_service_guard.h
pkg/trunk/util/misc_utils/include/misc_utils/job_queue.h
pkg/trunk/util/misc_utils/include/misc_utils/realtime_publisher.h
pkg/trunk/util/misc_utils/include/misc_utils/subscription_guard.h
pkg/trunk/util/misc_utils/manifest.xml
pkg/trunk/util/mux/mux.cpp
pkg/trunk/util/mux/switch.cpp
pkg/trunk/util/point_cloud_utils/include/point_cloud_utils/scan_assembler.h
pkg/trunk/util/point_cloud_utils/include/point_cloud_utils/timed_scan_assembler.h
pkg/trunk/util/point_cloud_utils/manifest.xml
pkg/trunk/util/point_cloud_utils/src/scan_assembler.cpp
pkg/trunk/util/point_cloud_utils/src/timed_scan_assembler.cpp
pkg/trunk/util/robot_self_filter/src/robotlinks_filter_node.cpp
pkg/trunk/util/tf/include/tf/message_notifier.h
pkg/trunk/util/tf/include/tf/transform_broadcaster.h
pkg/trunk/util/tf/include/tf/transform_datatypes.h
pkg/trunk/util/tf/include/tf/transform_listener.h
pkg/trunk/util/tf/src/transform_sender.cpp
pkg/trunk/util/tf/test/testBroadcaster.cpp
pkg/trunk/util/tf/test/testListener.cpp
pkg/trunk/util/tf/test/test_notifier.cpp
pkg/trunk/util/topic_synchronizer/manifest.xml
pkg/trunk/util/topic_synchronizer/topic_synchronizer.h
pkg/trunk/util/trajectory/include/trajectory/trajectory.h
pkg/trunk/vision/borg/borg.cpp
pkg/trunk/vision/calib_converter/src/calib_converter.cpp
pkg/trunk/vision/camera_grab_samples/bumblebee_grab_sample/bumblebee_grab_sample.cpp
pkg/trunk/vision/checkerboard_detector/checkerboard_detector.cpp
pkg/trunk/vision/color_calib/calib_node.cpp
pkg/trunk/vision/color_calib/calib_node_dcam.cpp
pkg/trunk/vision/color_calib/calibration.cpp
pkg/trunk/vision/color_calib/color_calib.h
pkg/trunk/vision/cv_view/dcam/cv_view.cpp
pkg/trunk/vision/cv_view/minimal/cv_view.cpp
pkg/trunk/vision/cv_view/src/cv_view.cpp
pkg/trunk/vision/cv_view/src/cv_view_array.cpp
pkg/trunk/vision/cv_view/src/cv_view_array_overlay.cpp
pkg/trunk/vision/cv_wrappers/src/cv_movie_streamer.cpp
pkg/trunk/vision/cv_wrappers/src/cv_view.cpp
pkg/trunk/vision/cv_wrappers/src/cv_view_array.cpp
pkg/trunk/vision/cv_wrappers/src/cv_view_array_overlay.cpp
pkg/trunk/vision/mech_turk/src/cv_mturk.cpp
pkg/trunk/vision/people/manifest.xml
pkg/trunk/vision/people/src/face_detection.cpp
pkg/trunk/vision/people/src/filter/people_tracking_node.cpp
pkg/trunk/vision/people/src/filter/people_tracking_node.h
pkg/trunk/vision/people/src/leg_detector.cpp
pkg/trunk/vision/people/src/stereo_face_color_tracker.cpp
pkg/trunk/vision/people/src/timing_diagnostics_node.cpp
pkg/trunk/vision/people/src/timing_diagnostics_node.h
pkg/trunk/vision/people/src/track_starter_gui.cpp
pkg/trunk/vision/spacetime_stereo/sts_dynamic.cpp
pkg/trunk/vision/spacetime_stereo/sts_node.cpp
pkg/trunk/vision/spectacles/specview/specview.cpp
pkg/trunk/vision/stereo_blob_tracker/src/axis_blob_tracker.cpp
pkg/trunk/vision/stereo_blob_tracker/src/blob_tracker_gui.cpp
pkg/trunk/vision/stereo_blob_tracker/src/listener.cpp
pkg/trunk/vision/stereo_blob_tracker/src/stereo_blob_tracker.cpp
pkg/trunk/vision/stereo_capture/src/project_light.cpp
pkg/trunk/vision/stereo_capture/src/stereo_capture.cpp
pkg/trunk/vision/stereo_image_proc/src/stereoproc.cpp
pkg/trunk/vision/stereo_view/stereo_view.cpp
pkg/trunk/vision/stereo_view/stereo_view_pixel_info.cpp
pkg/trunk/visualization/cloud_viewer/src/cloud_node/cloud_node.cpp
pkg/trunk/visualization/ogre_tools/src/ogre_tools/ortho_camera.cpp
pkg/trunk/visualization/ogre_tools/src/ogre_tools/shape.cpp
pkg/trunk/visualization/ogre_tools/test/utest.cpp
pkg/trunk/visualization/ogre_visualizer/manifest.xml
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/collision_map_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/collision_map_display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/octree_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/octree_display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/particle_cloud_2d_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/planning_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/point_cloud_base.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/point_cloud_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/point_cloud_display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/polygonal_map_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/polygonal_map_display.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/robot_base2d_pose_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/robot_model_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/factory.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/properties/property.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/properties/property.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/properties/property_manager.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/properties/property_manager.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/ros_topic_property.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/ros_topic_property.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/tools/tool.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_panel.h
pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp
pkg/trunk/visualization/ogre_visualizer/src/test/rgb_cloud_test.cpp
pkg/trunk/visualization/ogre_visualizer/src/test/visualizer_test.cpp
pkg/trunk/visualization/wx_camera_panel/src/wx_camera_panel/CameraPanel.cpp
pkg/trunk/visualization/wx_camera_panel/src/wx_camera_panel/CameraPanel.h
pkg/trunk/visualization/wx_camera_panel/src/wx_camera_panel/CameraSetupDialog.cpp
pkg/trunk/visualization/wx_camera_panel/src/wx_camera_panel/CameraSetupDialog.h
pkg/trunk/world_models/costmap_2d/include/costmap_2d/basic_observation_buffer.h
pkg/trunk/world_models/costmap_2d/manifest.xml
pkg/trunk/world_models/costmap_2d/src/costmap_2d.cpp
pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
pkg/trunk/world_models/costmap_2d/src/test/costmap2d_pqueue_benchmark.cpp
pkg/trunk/world_models/map_saver/src/map_saver.cpp
pkg/trunk/world_models/map_server/src/main.cpp
pkg/trunk/world_models/map_server/test/rtest.cpp
pkg/trunk/world_models/robot_models/robot_filter/include/robot_filter/RobotFilter.h
pkg/trunk/world_models/robot_models/robot_filter/src/robot_filter.cpp
pkg/trunk/world_models/robot_models/robot_model/include/robot_model/cnode.h
pkg/trunk/world_models/robot_models/robot_model/include/robot_model/knode.h
pkg/trunk/world_models/topological_map/include/topological_map/ros_bottleneck_graph.h
pkg/trunk/world_models/topological_map/src/bottleneck_graph.cpp
pkg/trunk/world_models/topological_map/src/roadmap.cpp
pkg/trunk/world_models/topological_map/src/ros_bottleneck_graph.cpp
pkg/trunk/world_models/world_3d_map/manifest.xml
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Added Paths:
-----------
pkg/trunk/vision/cv_wrappers/.build_version
pkg/trunk/vision/cv_wrappers/lib/
pkg/trunk/vision/image_synthesizer/bin/
pkg/trunk/vision/image_synthesizer/lib/
Removed Paths:
-------------
pkg/trunk/august-cleanup.py
pkg/trunk/util/misc_utils/include/misc_utils/mutex_guard.h
Property Changed:
----------------
pkg/trunk/
pkg/trunk/3rdparty/kdl/kdl-willow/debian/rules
pkg/trunk/controllers/robot_mechanism_controllers/
Property changes on: pkg/trunk
___________________________________________________________________
Modified: svk:merge
- 637b03a7-42c1-4bbd-8d43-e365e379942c:/rosTF_to_tf:9746
920d6130-5740-4ec1-bb1a-45963d5fd813:/frameidpr:7015
920d6130-5740-4ec1-bb1a-45963d5fd813:/users/josh-pr:11755
920d6130-5740-4ec1-bb1a-45963d5fd813:/wgpkgtrunk:5865
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/josh:9316
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/rosbus:261
+ 637b03a7-42c1-4bbd-8d43-e365e379942c:/rosTF_to_tf:9746
920d6130-5740-4ec1-bb1a-45963d5fd813:/frameidpr:7015
920d6130-5740-4ec1-bb1a-45963d5fd813:/users/josh-pr:11755
920d6130-5740-4ec1-bb1a-45963d5fd813:/wgpkgtrunk:5865
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/josh:9624
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/rosbus:261
Property changes on: pkg/trunk/3rdparty/kdl/kdl-willow/debian/rules
___________________________________________________________________
Deleted: svn:executable
- *
Modified: pkg/trunk/audio/audio_capture/audio_capture.cpp
===================================================================
--- pkg/trunk/audio/audio_capture/audio_capture.cpp 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/audio/audio_capture/audio_capture.cpp 2009-01-17 08:10:01 UTC (rev 9626)
@@ -33,7 +33,7 @@
#include "robot_msgs/AudioRawStream.h"
const static int SAMPLE_RATE = 44100; // todo: make this a parameter.
-ros::node *g_audio_node = NULL;
+ros::Node *g_audio_node = NULL;
bool g_caught_sigint = false;
#define SHOW_MAX_SAMPLE
@@ -92,7 +92,7 @@
}
ROS_DEBUG("opening default audio stream");
ros::init(argc, argv);
- ros::node n("audio_capture", ros::node::DONT_HANDLE_SIGINT);
+ ros::Node n("audio_capture", ros::Node::DONT_HANDLE_SIGINT);
g_audio_node = &n;
n.advertise<robot_msgs::AudioRawStream>("audio", 5);
err = Pa_OpenDefaultStream(&stream, 1, 0, paFloat32, SAMPLE_RATE, 4096,
Modified: pkg/trunk/audio/audio_capture/audio_clip_writer.cpp
===================================================================
--- pkg/trunk/audio/audio_capture/audio_clip_writer.cpp 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/audio/audio_capture/audio_clip_writer.cpp 2009-01-17 08:10:01 UTC (rev 9626)
@@ -45,7 +45,7 @@
class AudioWriter
{
public:
- AudioWriter(ros::node *n)
+ AudioWriter(ros::Node *n)
: clip_num(0), clip_start(0), clip_end(0), audio_clock(0),
clip_state(IDLE), window_power(0)
{
@@ -164,7 +164,7 @@
int main(int argc, char **argv)
{
ros::init(argc, argv);
- ros::node n("audio_clip_writer");
+ ros::Node n("audio_clip_writer");
AudioWriter *aw = new AudioWriter(&n);
while (n.ok())
ros::Duration(0, 500000000).sleep();
Deleted: pkg/trunk/august-cleanup.py
===================================================================
--- pkg/trunk/august-cleanup.py 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/august-cleanup.py 2009-01-17 08:10:01 UTC (rev 9626)
@@ -1,103 +0,0 @@
-#!/usr/env python
-
-import sys
-import os
-
-SVN = 'svn'
-SVN_REV_MIN = 2785
-PR_URL = 'https://personalrobots.svn.sf.net/svnroot/personalrobots/pkg/trunk'
-
-## ros package path
-rpp = os.environ['ROS_PACKAGE_PATH']
-
-# directories to purge
-dirs = [
- '3rdparty/drivers',
- '3rdparty/gazebo_git',
- 'messages',
- 'robot_models',
- 'services',
- 'simulator/tools',
- 'unported/vision',
- 'util/features',
- 'util/gui',
- 'util/scan_utils',
- 'util/transforms',
- ]
-
-# get the svn info for this dir
-
-from subprocess import Popen, PIPE
-
-svninfo = (Popen([SVN, 'info'], stdout=PIPE).communicate()[0] or '').strip().split('\n')
-
-# verify the current working directory is the same as personal robots
-
-import string
-svn_url = None
-for l in svninfo:
- vals = l.split(':')
- if vals[0] == 'URL':
- svn_url = ':'.join(vals[1:]).strip()
- print svn_url
-
- break
-else:
- print >> sys.stderr, "ERROR: unable to determine current SVN URL"
- sys.exit(1)
-if svn_url != PR_URL:
-
- #there are various setups in which this might be true, so check
- #against RPP instead, which isn't as strong
-
- print >> sys.stderr, "WARNING: svn info doesn't match, validating against ROS_PACKAGE_PATH instead"
-
- for d in rpp.split(':'):
- if os.path.samefile(d, '.'):
- rpp = d
- break
- else:
- print >> sys.stderr, "ERROR: this must be run from the personal robots directory"
- sys.exit(1)
-else:
- print "... SVN URL matches personalrobots"
-
-print "... validated current working directory"
-
-# verify the subversion rev number for this script
-
-import string
-svn_rev = None
-for l in svninfo:
- vals = l.split(':')
- if vals[0] == 'Revision':
- svn_rev = string.atoi(vals[1])
- break
-else:
- print >> sys.stderr, "ERROR: unable to determine current SVN revision"
- sys.exit(1)
-if svn_rev < SVN_REV_MIN:
- print >> sys.stderr, "ERROR: your personalrebots repository is out of date. This script is designed for SVN revision number [%s] or later"%SVN_REV_MIN
- sys.exit(1)
-else:
- print "... validated SVN revision number (%s >= %s)"%(svn_rev, SVN_REV_MIN)
-
-# delete the now dead directories
-print "... rub-a-dub-dub, here comes the scrub"
-import shutil
-import time
-for d in dirs:
- p = os.path.join(rpp, d)
- if not os.path.exists(p):
- continue
- sys.stdout.write("Delete [%s]? (y/n) "%p)
- answer = None
- while answer not in ['y', 'n']:
- answer = sys.stdin.readline().strip()
- if answer == 'n':
- print "... ignoring [%s]"%p
- else:
- print "... deleting [%s]"%p
- shutil.rmtree(p)
-
-print "... CLEAN!"
Modified: pkg/trunk/calibration/kinematic_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/manifest.xml 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/calibration/kinematic_calibration/manifest.xml 2009-01-17 08:10:01 UTC (rev 9626)
@@ -11,7 +11,7 @@
<depend package="topic_synchronizer" />
<depend package="image_msgs" />
<depend package="newmat10"/>
- <depend package="rosthread"/>
+ <depend package="boost"/>
<depend package="pr2_mechanism_controllers" />
<export>
<cpp cflags="-I${prefix}/msg/cpp"/>
Modified: pkg/trunk/calibration/kinematic_calibration/src/arm_phasespace_grabber.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/src/arm_phasespace_grabber.cpp 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/calibration/kinematic_calibration/src/arm_phasespace_grabber.cpp 2009-01-17 08:10:01 UTC (rev 9626)
@@ -1,13 +1,13 @@
/*********************************************************************
* Software License Agreement (BSD License)
-*
+*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
-*
+*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
-*
+*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
@@ -17,7 +17,7 @@
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
-*
+*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
@@ -35,7 +35,7 @@
#include <stdio.h>
#include "ros/node.h"
-#include "rosthread/mutex.h"
+#include "boost/thread/mutex.hpp"
#include "robot_msgs/MechanismState.h"
#include "robot_msgs/MocapSnapshot.h"
#include "robot_kinematics/robot_kinematics.h"
@@ -43,35 +43,35 @@
#include "kdl/chain.hpp"
#include <unistd.h>
-#include <termios.h>
+#include <termios.h>
using namespace std ;
namespace kinematic_calibration
{
-
-class ArmPhaseSpaceGrabber : public ros::node
+
+class ArmPhaseSpaceGrabber : public ros::Node
{
public:
-
-
- ArmPhaseSpaceGrabber() : ros::node("arm_phase_space_grabber")
+
+
+ ArmPhaseSpaceGrabber() : ros::Node("arm_phase_space_grabber")
{
marker_id_ = 1 ;
-
+
subscribe("phase_space_snapshot", snapshot_, &ArmPhaseSpaceGrabber::SnapshotCallback, 2) ;
subscribe("mechanism_state", mech_state_, &ArmPhaseSpaceGrabber::MechStateCallback, 2) ;
}
-
+
~ArmPhaseSpaceGrabber()
{
unsubscribe("phase_space_snapshot") ;
unsubscribe("MechanismState") ;
}
-
+
bool spin()
{
// Setup terminal settings for getchar
@@ -84,15 +84,15 @@
flags.c_cc[VMIN] = 0; // i.e. min 1 char for blocking, 0 chars for non-blocking
flags.c_cc[VTIME] = 0; // block if waiting for char
tcsetattr(fd,TCSANOW,&flags);
-
+
KDL::Chain chain ;
-
+
vector<string> joint_names ;
-
+
bool result ;
result = LoadJointNames("./joint_names.xml", joint_names) ;
-
-
+
+
const string state_data_filename = "./state_data.txt" ;
FILE* state_data_out ;
state_data_out = fopen(state_data_filename.c_str(), "w") ;
@@ -101,28 +101,28 @@
printf("Error opening state_data file\n") ;
return false ;
}
-
+
while (ok())
{
char c = getchar() ;
-
+
switch (c)
{
case ' ':
{
printf("Capturing...\n") ;
robot_msgs::MocapMarker cur_marker ;
-
+
//GetMarker(cur_marker, marker_id_) ;
vector<double> joint_angles ;
GetJointAngles(joint_names, joint_angles) ;
-
+
// Print Marker Location
printf("% 15.10f % 15.10f % 15.10f ", cur_marker.location.x, cur_marker.location.y, cur_marker.location.z) ;
fprintf(state_data_out, "% 15.10f % 15.10f % 15.10f ", cur_marker.location.x, cur_marker.location.y, cur_marker.location.z) ;
-
+
// Print Joint Angles
for (unsigned int i=0; i<joint_angles.size(); i++)
{
@@ -130,20 +130,20 @@
fprintf(state_data_out, "% 15.10f ", joint_angles[i]) ;
}
printf("\n") ;
-
+
break ;
- }
+ }
case 'c': // Build kinematic chain for arm
{
robot_kinematics::RobotKinematics robot_kinematics ;
string robot_desc ;
param("robotdesc/pr2", robot_desc, string("")) ;
printf("RobotDesc.length() = %u\n", (unsigned int)robot_desc.length()) ;
-
+
robot_kinematics.loadString(robot_desc.c_str()) ;
robot_kinematics::SerialChain* serial_chain = robot_kinematics.getSerialChain("right_arm") ;
-
+
if (serial_chain == NULL)
{
printf("Got NULL Chain\n") ;
@@ -162,7 +162,7 @@
printf("Error opening file\n") ;
break ;
}
-
+
for (unsigned int i=0; i < chain.getNrOfSegments(); i++)
{
printf("Segment #%u\n", i) ;
@@ -171,7 +171,7 @@
printf("% 15.10f ", chain.getSegment(i).getFrameToTip().p(j) ) ;
printf("\n") ;
-
+
KDL::Vector rot_axis ;
double rot_ang = chain.getSegment(i).getFrameToTip().M.GetRotAngle(rot_axis) ;
@@ -182,29 +182,29 @@
printf("\n") ;
printf(" Angle: % 15.10f\n", rot_ang) ;
- KDL::Vector rot_vec = rot_ang * rot_axis ;
-
+ KDL::Vector rot_vec = rot_ang * rot_axis ;
+
for (unsigned int j=0; j<3; j++)
fprintf(model_out, "% 15.10f ", chain.getSegment(i).getFrameToTip().p(j) ) ;
for (unsigned int j=0; j<3; j++)
fprintf(model_out, "% 15.10f ", rot_vec(j)) ;
fprintf(model_out, "\n") ;
-
-
+
+
//printf(" Product: ") ;
//for (unsigned int j=0; j<3; j++)
// printf("% 15.10f ", rot_vec(j)) ;
printf("\n\n") ;
}
fclose(model_out) ;
-
+
break ;
- }
+ }
default:
break ;
}
-
+
usleep(1000) ;
fflush(stdout) ;
}
@@ -213,16 +213,16 @@
tcsetattr(fd,TCSANOW, &prev_flags) ; // Undo any terminal changes that we made
return true ;
}
-
+
bool LoadJointNames(const string& joint_names_file, vector<string>& joint_names)
{
TiXmlDocument xml ;
xml.LoadFile(joint_names_file.c_str()) ;
TiXmlElement *config = xml.RootElement();
-
+
if (config == NULL)
return false ;
-
+
// Extract the joint names
TiXmlElement *joint_name_elem = config->FirstChildElement("joint_name") ;
@@ -232,22 +232,22 @@
const char* name = joint_name_elem->Attribute("name") ;
printf("Found a joint_name: %s\n", name) ;
joint_names.push_back(name) ;
-
+
joint_name_elem = joint_name_elem->NextSiblingElement("joint_name") ;
}
return true ;
}
-
+
void GetMarker(robot_msgs::MocapMarker& marker, int id)
{
bool marker_found = false ;
-
+
// Grab phasespace marker
printf(" Looking for marker %u...", id) ;
fflush(stdout) ;
while (ok() && !marker_found)
{
-
+
snapshot_lock_.lock() ;
for (unsigned int i=0; i < safe_snapshot_.get_markers_size(); i++)
{
@@ -266,16 +266,16 @@
usleep(100) ;
}
}
-
+
void GetJointAngles(const vector<string>& names, vector<double>& angles)
{
// Grab mechanism state and put it in a local copy
mech_lock_.lock() ;
robot_msgs::MechanismState mech_state = safe_mech_state_ ;
- mech_lock_.unlock() ;
-
+ mech_lock_.unlock() ;
+
angles.resize(names.size()) ;
-
+
for (unsigned int i=0; i < names.size(); i++)
{
for (unsigned int j=0; j < mech_state.get_joint_states_size(); j++)
@@ -288,32 +288,32 @@
}
}
}
-
+
void MechStateCallback()
{
mech_lock_.lock() ;
safe_mech_state_ = mech_state_ ;
mech_lock_.unlock() ;
}
-
+
void SnapshotCallback()
{
snapshot_lock_.lock() ;
safe_snapshot_ = snapshot_ ;
snapshot_lock_.unlock() ;
}
-
+
private:
robot_msgs::MocapSnapshot snapshot_ ;
robot_msgs::MechanismState mech_state_ ;
robot_msgs::MocapSnapshot safe_snapshot_ ;
int marker_id_ ;
-
+
robot_msgs::MechanismState safe_mech_state_ ;
-
- ros::thread::mutex mech_lock_ ;
- ros::thread::mutex snapshot_lock_ ;
+
+ boost::mutex mech_lock_ ;
+ boost::mutex snapshot_lock_ ;
} ;
}
@@ -323,11 +323,11 @@
int main(int argc, char** argv)
{
ros::init(argc, argv) ;
-
- ArmPhaseSpaceGrabber grabber ;
+
+ ArmPhaseSpaceGrabber grabber ;
grabber.spin() ;
-
+
ros::fini() ;
-
+
return 0 ;
}
Modified: pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp 2009-01-17 08:10:01 UTC (rev 9626)
@@ -1,13 +1,13 @@
/*********************************************************************
* Software License Agreement (BSD License)
-*
+*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
-*
+*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
-*
+*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
@@ -17,7 +17,7 @@
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
-*
+*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
@@ -35,7 +35,7 @@
#include <stdio.h>
#include "ros/node.h"
-#include "rosthread/mutex.h"
+#include "boost/thread/mutex.hpp"
#include "robot_msgs/MechanismState.h"
#include "robot_msgs/MocapSnapshot.h"
@@ -49,7 +49,7 @@
#include "topic_synchronizer.h" // From package topic_synchronizer
#include <unistd.h>
-#include <termios.h>
+#include <termios.h>
using namespace std ;
@@ -63,13 +63,13 @@
* mechanism state. When the <spacebar> is hit, this node published a
* "meta-packet" that contains the latest information from all of these data
* sources.
- *
+ *
* And standard use case would be to capture sensor data of still checkerboard
* in the environment and then hit spacebar to record all the sensor data at once
* to a bag file. We can then move the checkerboard and robot, and capture a new
* datapoint.
*/
-class SensorKinematicsGrabber : public ros::node
+class SensorKinematicsGrabber : public ros::Node
{
public:
@@ -78,7 +78,7 @@
robot_msgs::MechanismState mech_state_ ;
robot_msgs::MechanismState safe_mech_state_ ;
- ros::thread::mutex mech_state_lock_ ;
+ boost::mutex mech_state_lock_ ;
// dcam subscription callback messages
image_msgs::Image left_image_ ;
@@ -95,22 +95,22 @@
image_msgs::StereoInfo safe_stereo_info_ ;
image_msgs::CamInfo safe_left_info_ ;
image_msgs::CamInfo safe_right_info_ ;
- ros::thread::mutex dcam_lock_ ;
+ boost::mutex dcam_lock_ ;
std_msgs::PointCloud laser_cloud_ ;
std_msgs::PointCloud safe_laser_cloud_ ;
- ros::thread::mutex laser_cloud_lock_ ;
-
+ boost::mutex laser_cloud_lock_ ;
+
// Parameters
bool subscribe_color_ ;
string output_topic_ ; // Topic name for publishing our SensorKinematics metapacket
-
- SensorKinematicsGrabber() : ros::node("sensor_kinematics_grabber"),
+
+ SensorKinematicsGrabber() : ros::Node("sensor_kinematics_grabber"),
dcam_sync_(this, &SensorKinematicsGrabber::dcamCallback, ros::Duration().fromSec(0.05), &SensorKinematicsGrabber::dcamCallbackTimeout)
{
param("~subscribe_color", subscribe_color_, false);
param("~output_topic", output_topic_, string("sensor_kinematics"));
-
+
// Stereo Cam Synchronized Subscriptions
if (subscribe_color_)
{
@@ -129,7 +129,7 @@
subscribe("mechanism_state", mech_state_, &SensorKinematicsGrabber::mechStateCallback, 2) ;
subscribe("tilt_laser_cloud", laser_cloud_, &SensorKinematicsGrabber::laserCloudCallback, 1) ;
-
+
advertise<SensorKinematics>(output_topic_, 1) ;
}
@@ -153,7 +153,7 @@
bool need_to_quit = false ;
unsigned int capture_count = 0 ;
-
+
while (ok() && !need_to_quit)
{
char c = getchar() ;
@@ -175,19 +175,19 @@
all_data.right_info = safe_right_info_ ;
all_data.left_info = safe_left_info_ ;
dcam_lock_.unlock() ;
-
+
laser_cloud_lock_.lock() ;
all_data.laser_cloud = safe_laser_cloud_ ;
laser_cloud_lock_.unlock() ;
-
+
mech_state_lock_.lock() ;
all_data.mechanism_state = safe_mech_state_ ;
mech_state_lock_.unlock() ;
-
+
displayAllInfo(all_data) ;
-
+
publish(output_topic_, all_data) ;
-
+
break ;
}
case EOF: // Means that we didn't catch any keyboard hits
@@ -202,11 +202,11 @@
}
}
} ;
-
+
tcsetattr(fd,TCSANOW, &prev_flags) ; // Undo any terminal changes that we made
return true ;
}
-
+
void mechStateCallback()
{
mech_state_lock_.lock() ;
@@ -231,16 +231,16 @@
safe_stereo_info_ = stereo_info_ ;
safe_left_info_ = left_info_ ;
safe_right_info_ = right_info_ ;
-
+
dcam_lock_.unlock() ;
}
-
+
void dcamCallbackTimeout(ros::Time t)
{
ROS_WARN("SensorKinematicsGrabber::DCam Synchronizer Timeout") ;
}
-
-
+
+
/**
* Display some basic information about all the different data types that we
* just captured. This lets us check if we're running into any serious
@@ -252,7 +252,7 @@
ros::Time cur_time = ros::Time::now() ;
ros::Duration lag ;
-
+
lag = data.left_image.header.stamp-cur_time ;
if (data.left_image.uint8_data.layout.get_dim_size() < 2)
printf(" Left Image: %lf [NO DATA]\n", lag.to_double()) ;
@@ -266,14 +266,14 @@
else
printf(" Right Image: %lf (%u, %u)\n", lag.to_double(), data.right_image.uint8_data.layout.dim[0].size,
data.right_image.uint8_data.layout.dim[1].size) ;
-
+
lag = data.disparity_image.header.stamp-cur_time ;
if (data.disparity_image.uint8_data.layout.get_dim_size() < 2)
printf(" Disparity Image: %lf [NO DATA]\n", lag.to_double()) ;
else
printf(" Disparity Image: %lf (%u, %u)\n", lag.to_double(), data.disparity_image.uint8_data.layout.dim[0].size,
data.disparity_image.uint8_data.layout.dim[1].size) ;
-
+
lag = data.stereo_info.header.stamp-cur_time ;
printf(" Stereo Info: %lf\n", lag.to_double()) ;
@@ -282,18 +282,18 @@
lag = data.right_info.header.stamp-cur_time ;
printf(" Right Info: %lf\n", lag.to_double()) ;
-
+
lag = data.mechanism_state.header.stamp-cur_time ;
printf(" Mechanism State: %lf %u Joints\n", lag.to_double(), data.mechanism_state.get_joint_states_size()) ;
-
+
lag = data.laser_cloud.header.stamp-cur_time ;
printf(" Laser Cloud: %lf %u points\n", lag.to_double(), data.laser_cloud.get_pts_size() ) ;
-
+
lag = data.phase_space_snapshot.header.stamp-cur_time ;
printf(" PhaseSpace: %lf %u Markers | %u Bodies\n", lag.to_double(), data.phase_space_snapshot.get_markers_size(),
data.phase_space_snapshot.get_bodies_size()) ;
- }
-
+ }
+
} ;
}
Modified: pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml 2009-01-17 08:10:01 UTC (rev 9626)
@@ -7,5 +7,5 @@
<depend package="std_msgs" />
<depend package="roscpp" />
<depend package="pr2_mechanism_controllers" />
- <depend package="rosthread" />
+ <depend package="boost" />
</package>
Modified: pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp 2009-01-17 08:10:01 UTC (rev 9626)
@@ -47,7 +47,7 @@
{
// constructor
odom_calib::odom_calib()
- : ros::node("odom_calibration"),
+ : ros::Node("odom_calibration"),
_odom_active(false),
_imu_active(false),
_completed(false)
Modified: pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h 2009-01-17 08:10:01 UTC (rev 9626)
@@ -36,7 +36,7 @@
// ros stuff
#include <ros/node.h>
-#include <rosthread/mutex.h>
+#include <boost/thread/mutex.hpp>
#include <tf/tf.h>
#include <pr2_mechanism_controllers/WheelRadiusMultiplier.h>
@@ -50,7 +50,7 @@
namespace calibration
{
-class odom_calib: public ros::node
+class odom_calib: public ros::Node
{
public:
/// constructor
@@ -101,7 +101,7 @@
std::vector<double> _mech_begin, _mech_end;
// mutex
- ros::thread::mutex _odom_mutex, _imu_mutex, _mech_mutex;
+ boost::mutex _odom_mutex, _imu_mutex, _mech_mutex;
}; // class
Modified: pkg/trunk/controllers/control_toolbox/src/serialchain_model.cpp
===================================================================
--- pkg/trunk/controllers/control_toolbox/src/serialchain_model.cpp 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/controllers/control_toolbox/src/serialchain_model.cpp 2009-01-17 08:10:01 UTC (rev 9626)
@@ -33,7 +33,7 @@
*********************************************************************/
#include <control_toolbox/serialchain_model.h>
- #include <rosconsole/rosconsole.h>
+ #include <ros/console.h>
#include <Eigen/LU>
bool SerialChainModel::init(const std::string & robot_description, const std::string & chain_name)
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_dynamics_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_dynamics_controller.h 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_dynamics_controller.h 2009-01-17 08:10:01 UTC (rev 9626)
@@ -35,7 +35,7 @@
#pragma once
#include <ros/node.h>
-#include <rosthread/mutex.h>
+#include <boost/thread/mutex.hpp>
#include <mechanism_model/controller.h>
#include <mechanism_model/joint.h>
@@ -112,7 +112,7 @@
*/
virtual void update(void); // Real time safe.
- ros::thread::mutex arm_controller_lock_;
+ boost::mutex arm_controller_lock_;
// void setJointGains(const pr2_mechanism_controllers::SetJointGains::request &req);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_position_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_position_controller.h 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_position_controller.h 2009-01-17 08:10:01 UTC (rev 9626)
@@ -35,7 +35,7 @@
#pragma once
#include <ros/node.h>
-#include <rosthread/mutex.h>
+#include <boost/thread/mutex.hpp>
#include <mechanism_model/controller.h>
#include <robot_mechanism_controllers/joint_position_controller.h>
@@ -126,7 +126,7 @@
*/
virtual void update(void); // Real time safe.
- ros::thread::mutex arm_controller_lock_;
+ boost::mutex arm_controller_lock_;
// void setJointGains(const pr2_mechanism_controllers::SetJointGains::request &req);
@@ -299,7 +299,7 @@
/*
* \brief pointer to ros node
*/
- ros::node * const node_;
+ ros::Node * const node_;
};
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h 2009-01-17 08:10:01 UTC (rev 9626)
@@ -35,7 +35,7 @@
#pragma once
#include <ros/node.h>
-#include <rosthread/mutex.h>
+#include <boost/thread/mutex.hpp>
#include <mechanism_model/controller.h>
#include <robot_mechanism_controllers/joint_position_controller.h>
@@ -109,7 +109,7 @@
*/
virtual void update(void); // Real time safe.
- ros::thread::mutex arm_controller_lock_;
+ boost::mutex arm_controller_lock_;
controller::JointPDController* getJointControllerByName(std::string name);
@@ -222,7 +222,7 @@
/*!
* \brief mutex lock for setting and getting ros messages
*/
- ros::thread::mutex ros_lock_;
+ boost::mutex ros_lock_;
pr2_mechanism_controllers::JointTraj traj_msg_;
@@ -247,7 +247,7 @@
/*
* \brief pointer to ros node
*/
- ros::node * const node_;
+ ros::Node * const node_;
/*
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_velocity_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_velocity_controller.h 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_velocity_controller.h 2009-01-17 08:10:01 UTC (rev 9626)
@@ -35,7 +35,7 @@
#pragma once
#include <ros/node.h>
-#include <rosthread/mutex.h>
+#include <boost/thread/mutex.hpp>
#include <mechanism_model/controller.h>
#include <robot_mechanism_controllers/joint_velocity_controller.h>
@@ -98,7 +98,7 @@
*/
virtual void update(void); // Real time safe.
- ros::thread::mutex arm_controller_lock_;
+ boost::mutex arm_controller_lock_;
void setJointGains(const pr2_mechanism_controllers::SetJointGains::request &req);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h 2009-01-17 08:10:01 UTC (rev 9626)
@@ -468,7 +468,7 @@
/*!
* \brief mutex lock for setting and getting ros messages
*/
- ros::thread::mutex ros_lock_;
+ boost::mutex ros_lock_;
/*!
* \brief std_msgs representation of an odometry message
@@ -492,7 +492,7 @@
/*
* \brief pointer to ros node
*/
- ros::node *node;
+ ros::Node *node;
/*
* \brief save service name prefix for unadvertise on exit
*/
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h 2009-01-17 07:55:56 UTC (rev 9625)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h 2009-01-17 08:10:01 UTC (rev 9626)
@@ -486,7 +486,7 @@
/*!
* \brief mutex lock for setting and getting ros messages
*/
- ros::thread::mutex ros_lock_;
+ boost::mutex ros_lock_;
/*!
* \brief std_msgs representation of an odometry message
@@ -512,7 +512,7 @@
/*
* \brief pointer to ros node
*/
- ros::node *node;
+ ros::Node *node;
/*
* \brief save service name prefix for unadvertise on exit
*/
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_position_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_position_controller.h 2009-01-1...
[truncated message content] |