├── README.md ├── Screenshot 1.jpg ├── Screenshot 2.jpg ├── Screenshot 3.jpg ├── ardrone_autonomy ├── .gitignore ├── .travis.yml ├── CHANGELOG.rst ├── CMakeLists.txt ├── LICENSE ├── Makefile ├── README.md ├── data │ └── camera_info │ │ ├── ardrone_bottom.yaml │ │ └── ardrone_front.yaml ├── docs │ ├── FAQ.rst │ ├── Makefile │ ├── commands.rst │ ├── conf.py │ ├── contributers.rst │ ├── frames.rst │ ├── images │ │ └── frames.jpg │ ├── index.rst │ ├── installation.rst │ ├── license.rst │ ├── parameters.rst │ ├── reading.rst │ ├── run.rst │ ├── services.rst │ └── usage.rst ├── include │ └── ardrone_autonomy │ │ ├── NavdataMessageDefinitions.h │ │ ├── ardrone_driver.h │ │ ├── ardrone_sdk.h │ │ ├── snippet_configure_drone.h │ │ ├── snippet_ros_to_ardrone_config.h │ │ ├── teleop_twist.h │ │ └── video.h ├── launch │ ├── ardrone.launch │ ├── ardrone_aggressive.launch │ └── ardrone_group.launch ├── mainpage.dox ├── msg │ ├── Navdata.msg │ ├── matrix33.msg │ ├── navdata_adc_data_frame.msg │ ├── navdata_altitude.msg │ ├── navdata_demo.msg │ ├── navdata_euler_angles.msg │ ├── navdata_games.msg │ ├── navdata_gyros_offsets.msg │ ├── navdata_hdvideo_stream.msg │ ├── navdata_kalman_pressure.msg │ ├── navdata_magneto.msg │ ├── navdata_phys_measures.msg │ ├── navdata_pressure_raw.msg │ ├── navdata_pwm.msg │ ├── navdata_raw_measures.msg │ ├── navdata_rc_references.msg │ ├── navdata_references.msg │ ├── navdata_time.msg │ ├── navdata_trackers_send.msg │ ├── navdata_trims.msg │ ├── navdata_video_stream.msg │ ├── navdata_vision.msg │ ├── navdata_vision_detect.msg │ ├── navdata_vision_of.msg │ ├── navdata_vision_perf.msg │ ├── navdata_vision_raw.msg │ ├── navdata_watchdog.msg │ ├── navdata_wifi.msg │ ├── navdata_wind_speed.msg │ ├── navdata_zimmu_3000.msg │ ├── vector21.msg │ └── vector31.msg ├── package.xml ├── rosdep.yaml ├── rosdoc.yaml ├── scripts │ ├── CreateNavdataFormat.py │ ├── NavdataMessageDefinitionsTemplate.c │ └── README.md ├── src │ ├── ardrone_driver.cpp │ ├── ardrone_sdk.cpp │ ├── teleop_twist.cpp │ └── video.cpp └── srv │ ├── CamSelect.srv │ ├── FlightAnim.srv │ ├── LedAnim.srv │ └── RecordEnable.srv ├── ardrone_simulator_gazebo7 ├── README.md ├── cvg_sim_gazebo │ ├── CMakeLists.txt │ ├── launch │ │ ├── ar_tag.launch │ │ ├── empty_world.launch │ │ ├── scoutrobot.launch │ │ ├── scoutrobot_world_1.launch │ │ ├── scoutrobot_world_2.launch │ │ ├── scoutrobot_world_3.launch │ │ ├── spawn_quadrotor.launch │ │ └── spawn_quadrotor_2.launch │ ├── meshes │ │ ├── ar_track_alvar_tags │ │ │ ├── ar_alvar_tag0 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ ├── ar_alvar_tag1 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ ├── ar_alvar_tag2 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ ├── ar_alvar_tag3 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ ├── ar_alvar_tag4 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ ├── ar_alvar_tag5 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ ├── ar_alvar_tag6 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ ├── ar_alvar_tag7 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ ├── ar_alvar_tag8 │ │ │ │ ├── meshes │ │ │ │ │ ├── MarkerData_0.png │ │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ │ └── ar_alvar_tag9 │ │ │ │ ├── meshes │ │ │ │ ├── MarkerData_0.png │ │ │ │ └── artag.dae │ │ │ │ ├── model.config │ │ │ │ └── model.sdf │ │ ├── hokuyo_utm30lx │ │ │ ├── blender │ │ │ │ └── hokuyo_utm30lx.blend │ │ │ ├── hokuyo_utm_30lx.dae │ │ │ ├── hokuyo_utm_30lx.stl │ │ │ └── hokuyo_utm_30lxTEST_SELF_FILTER.dae │ │ ├── kinect_camera │ │ │ ├── kinect_camera_simple.dae │ │ │ └── kinect_camera_simple.stl │ │ ├── quadrotor │ │ │ ├── blender │ │ │ │ ├── quadrotor_2.blend │ │ │ │ ├── quadrotor_2.blend1 │ │ │ │ ├── quadrotor_3.blend1 │ │ │ │ ├── quadrotor_CAD.blend │ │ │ │ ├── quadrotor_CAD2.blend │ │ │ │ ├── quadrotor_CAD2.blend1 │ │ │ │ ├── quadrotor_CAD2.blend2 │ │ │ │ └── quadrotor_base.blend │ │ │ ├── quadrotor_2.dae │ │ │ ├── quadrotor_2.stl │ │ │ ├── quadrotor_3.dae │ │ │ ├── quadrotor_3.stl │ │ │ ├── quadrotor_4.dae │ │ │ ├── quadrotor_4.stl │ │ │ ├── quadrotor_base.dae │ │ │ └── quadrotor_base.stl │ │ ├── sonar_sensor │ │ │ ├── blender │ │ │ │ └── max_sonar_ez4.blend │ │ │ └── max_sonar_ez4.dae │ │ └── thermaleye_camera │ │ │ ├── thermaleye_camera_hector_v1.dae │ │ │ ├── thermaleye_camera_hector_v1.stl │ │ │ ├── thermaleye_camera_hector_v2.dae │ │ │ └── thermaleye_camera_hector_v2.stl │ ├── package.xml │ ├── urdf │ │ ├── moveit_demo.urdf.xacro │ │ ├── quadrotor.urdf.xacro │ │ ├── quadrotor_base.urdf.xacro │ │ ├── quadrotor_base.urdf.xacro.original │ │ ├── quadrotor_sensors.urdf.xacro │ │ ├── sensors │ │ │ ├── generic_camera.urdf.xacro │ │ │ ├── hokuyo_utm30lx.urdf.xacro │ │ │ ├── kinect.urdf.xacro │ │ │ ├── sonar_sensor.urdf.xacro │ │ │ └── velodyne.urdf.xacro │ │ └── velodyne_definition │ └── worlds │ │ ├── ar_tag_alvar_multiple.world │ │ ├── ardrone_custom.world │ │ ├── ardrone_freeway.world │ │ ├── ardrone_mazelike.world │ │ ├── ardrone_mazelike_topless.world │ │ ├── ardrone_testworld.world │ │ ├── ardrone_walled_city.world │ │ ├── ardrone_walls.world │ │ ├── gaz │ │ ├── scoutrobot_world.world │ │ ├── scoutrobot_world2.world │ │ ├── scoutrobot_world2b.world │ │ ├── scoutrobot_world3.world │ │ ├── scoutrobot_world4.world │ │ ├── scoutrobot_world_1.world │ │ ├── scoutrobot_world_2.world │ │ ├── scoutrobot_world_2b.world │ │ ├── scoutrobot_world_3.world │ │ └── test1 ├── cvg_sim_gazebo_plugins │ ├── CMakeLists.txt │ ├── include │ │ ├── hector_gazebo_plugins │ │ │ ├── diffdrive_plugin_6w.h │ │ │ ├── gazebo_ros_gps.h │ │ │ ├── gazebo_ros_imu.h │ │ │ ├── gazebo_ros_magnetic.h │ │ │ ├── gazebo_ros_sonar.h │ │ │ ├── reset_plugin.h │ │ │ └── sensor_model.h │ │ ├── hector_quadrotor_controller │ │ │ ├── quadrotor_simple_controller.h │ │ │ └── quadrotor_state_controller.h │ │ └── hector_quadrotor_gazebo_plugins │ │ │ └── gazebo_ros_baro.h │ ├── package.xml │ ├── src │ │ ├── cvg_sim_gazebo_plugins │ │ │ └── __init__.py │ │ ├── diffdrive_plugin_6w.cpp │ │ ├── gazebo_ros_baro.cpp │ │ ├── gazebo_ros_gps.cpp │ │ ├── gazebo_ros_imu.cpp │ │ ├── gazebo_ros_magnetic.cpp │ │ ├── gazebo_ros_sonar.cpp │ │ ├── quadrotor_simple_controller.cpp │ │ ├── quadrotor_state_controller.cpp │ │ ├── reset_plugin.cpp │ │ └── test_trajectory.cpp │ ├── srv │ │ └── SetBias.srv │ └── urdf │ │ ├── quadrotor_plugins.urdf.xacro │ │ ├── quadrotor_sensors.urdf.xacro │ │ └── quadrotor_simple_controller.urdf.xacro ├── cvg_sim_msgs │ ├── CMakeLists.txt │ ├── include │ │ └── cvg_sim_msgs │ │ │ ├── ControlSource.h │ │ │ └── RC │ │ │ └── functions.h │ ├── msg │ │ ├── Altimeter.msg │ │ ├── Altitude.msg │ │ ├── AttitudeCommand.msg │ │ ├── Compass.msg │ │ ├── ControllerState.msg │ │ ├── HeadingCommand.msg │ │ ├── HeightCommand.msg │ │ ├── MotorCommand.msg │ │ ├── MotorPWM.msg │ │ ├── MotorStatus.msg │ │ ├── PositionXYCommand.msg │ │ ├── RC.msg │ │ ├── RawImu.msg │ │ ├── RawMagnetic.msg │ │ ├── RawRC.msg │ │ ├── RuddersCommand.msg │ │ ├── ServoCommand.msg │ │ ├── Supply.msg │ │ ├── ThrustCommand.msg │ │ ├── VelocityXYCommand.msg │ │ ├── VelocityZCommand.msg │ │ └── YawrateCommand.msg │ ├── package.xml │ └── src │ │ └── cvg_sim_msgs │ │ └── __init__.py ├── message_to_tf │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ │ └── message_to_tf.cpp └── tum_simulator │ ├── CMakeLists.txt │ └── package.xml ├── driver_common ├── driver_base │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── driver_base │ │ │ ├── driver.h │ │ │ └── driver_node.h │ ├── mainpage.dox │ ├── msg │ │ ├── ConfigString.msg │ │ ├── ConfigValue.msg │ │ └── SensorLevels.msg │ └── package.xml ├── driver_common │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml └── timestamp_tools │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ └── timestamp_tools │ │ ├── periodic_timestamp_min_filter.h │ │ └── trigger_matcher.h │ ├── mainpage.dox │ ├── package.xml │ └── test │ └── test_trigger_matcher.cpp ├── hector_models ├── README.md ├── hector_components_description │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── meshes │ │ ├── checkerboard │ │ │ ├── checkerboard.dae │ │ │ ├── checkerboard.png │ │ │ └── checkerboard.stl │ │ ├── hector_multisensor_head │ │ │ ├── multisensor_head.stl │ │ │ └── multisensor_head_collision.stl │ │ ├── kalibr_targets │ │ │ ├── april_50x50cm_A0_1024px.dae │ │ │ └── april_50x50cm_A0_1024px.png │ │ └── vision_box │ │ │ ├── HectorDarmstadt_TU_Darmstadt_combined_with_background_cut_256.png │ │ │ ├── hector1_top_box.dae │ │ │ ├── hector1_top_box.stl │ │ │ ├── hector1_top_boxTEST_SELF_FILTER.dae │ │ │ ├── hector2_top_box.dae │ │ │ ├── hector2_top_box.stl │ │ │ ├── hector2_top_boxTEST_SELF_FILTER.dae │ │ │ └── ps_eye_simple.dae │ ├── package.xml │ └── urdf │ │ ├── autonomy_box.urdf.xacro │ │ ├── checkerboard.urdf.xacro │ │ ├── dual_hokuyo_mount.urdf.xacro.xml │ │ ├── headlight.urdf.xacro │ │ ├── hector_multisensor_head.urdf.xacro │ │ ├── kalibr_april_50x50cm_A0_1024px.urdf.xacro │ │ ├── spinning_hokuyo_utm30lx.urdf.xacro │ │ ├── spinning_lidar_mount.urdf.xacro │ │ ├── tracker_sensor_head.urdf.xacro.xml │ │ ├── vision_box_common.gazebo.xacro │ │ ├── vision_box_common.urdf.xacro │ │ ├── vision_box_common_dimensions.urdf.xacro │ │ ├── vision_box_dimensions_hector1.urdf.xacro │ │ ├── vision_box_dimensions_hector2.urdf.xacro │ │ ├── vision_box_hector1_addons.urdf.xacro │ │ ├── vision_box_hector2_addons.urdf.xacro │ │ └── vlp16_mount.urdf.xacro.xml ├── hector_models.rosinstall ├── hector_models │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml ├── hector_sensors_description │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── meshes │ │ ├── asus_camera │ │ │ ├── asus_camera_simple.dae │ │ │ └── asus_camera_simple.stl │ │ ├── hokuyo_utm30lx │ │ │ ├── blender │ │ │ │ └── hokuyo_utm30lx.blend │ │ │ ├── hokuyo_utm_30lx.dae │ │ │ ├── hokuyo_utm_30lx.stl │ │ │ └── hokuyo_utm_30lxTEST_SELF_FILTER.dae │ │ ├── kinect_camera │ │ │ ├── kinect_camera_simple.dae │ │ │ └── kinect_camera_simple.stl │ │ ├── sonar_sensor │ │ │ ├── blender │ │ │ │ └── max_sonar_ez4.blend │ │ │ └── max_sonar_ez4.dae │ │ └── thermaleye_camera │ │ │ ├── thermaleye_camera_hector_v1.dae │ │ │ ├── thermaleye_camera_hector_v1.stl │ │ │ ├── thermaleye_camera_hector_v2.dae │ │ │ └── thermaleye_camera_hector_v2.stl │ ├── package.xml │ └── urdf │ │ ├── asus_camera.urdf.xacro │ │ ├── camera360.urdf.xacro │ │ ├── flir_a35_camera.urdf.xacro │ │ ├── generic_camera.urdf.xacro │ │ ├── generic_stereo_camera.urdf.xacro │ │ ├── generic_thermal_camera.urdf.xacro │ │ ├── generic_zoom_camera.urdf.xacro │ │ ├── hokuyo_utm30lx.urdf.xacro │ │ ├── kinect_camera.urdf.xacro │ │ ├── realsense_camera.urdf.xacro │ │ ├── realsense_d435_camera.urdf.xacro │ │ ├── ricoh_theta.urdf.xacro │ │ ├── sonar_sensor.urdf.xacro │ │ ├── thermaleye_camera.urdf.xacro │ │ └── vlp16.urdf.xacro └── hector_xacro_tools │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── urdf │ ├── inertia_tensors.urdf.xacro │ ├── joint_macros.urdf.xacro │ └── sensor_macros.urdf.xacro ├── hector_slam ├── .gitignore ├── README.txt ├── hector_compressed_map_transport │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ │ └── map_to_image_node.cpp ├── hector_geotiff │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── hector_geotiff │ │ │ ├── geotiff_writer.h │ │ │ ├── map_writer_interface.h │ │ │ └── map_writer_plugin_interface.h │ ├── launch │ │ ├── geotiff_mapper.launch │ │ └── geotiff_mapper_only.launch │ ├── package.xml │ └── src │ │ ├── geotiff_node.cpp │ │ ├── geotiff_saver.cpp │ │ └── geotiff_writer │ │ └── geotiff_writer.cpp ├── hector_geotiff_plugins │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── hector_geotiff_plugins.xml │ ├── package.xml │ └── src │ │ └── trajectory_geotiff_plugin.cpp ├── hector_imu_attitude_to_tf │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ └── example.launch │ ├── package.xml │ └── src │ │ └── imu_attitude_to_tf_node.cpp ├── hector_imu_tools │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── bertl_robot.launch │ │ └── jasmine_robot.launch │ ├── package.xml │ └── src │ │ └── pose_and_orientation_to_imu_node.cpp ├── hector_map_server │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ │ └── hector_map_server.cpp ├── hector_map_tools │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── hector_map_tools │ │ │ └── HectorMapTools.h │ └── package.xml ├── hector_mapping │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── hector_slam_lib │ │ │ ├── map │ │ │ ├── GridMap.h │ │ │ ├── GridMapBase.h │ │ │ ├── GridMapCacheArray.h │ │ │ ├── GridMapLogOdds.h │ │ │ ├── GridMapReflectanceCount.h │ │ │ ├── GridMapSimpleCount.h │ │ │ ├── MapDimensionProperties.h │ │ │ ├── OccGridMapBase.h │ │ │ ├── OccGridMapUtil.h │ │ │ └── OccGridMapUtilConfig.h │ │ │ ├── matcher │ │ │ └── ScanMatcher.h │ │ │ ├── scan │ │ │ └── DataPointContainer.h │ │ │ ├── slam_main │ │ │ ├── HectorSlamProcessor.h │ │ │ ├── MapProcContainer.h │ │ │ ├── MapRepMultiMap.h │ │ │ ├── MapRepSingleMap.h │ │ │ └── MapRepresentationInterface.h │ │ │ └── util │ │ │ ├── DrawInterface.h │ │ │ ├── HectorDebugInfoInterface.h │ │ │ ├── MapLockerInterface.h │ │ │ └── UtilFunctions.h │ ├── launch │ │ └── mapping_default.launch │ ├── msg │ │ ├── HectorDebugInfo.msg │ │ └── HectorIterData.msg │ ├── package.xml │ └── src │ │ ├── HectorDebugInfoProvider.h │ │ ├── HectorDrawings.h │ │ ├── HectorMapMutex.h │ │ ├── HectorMappingRos.cpp │ │ ├── HectorMappingRos.h │ │ ├── PoseInfoContainer.cpp │ │ ├── PoseInfoContainer.h │ │ ├── main.cpp │ │ └── main_mapper.cpp ├── hector_marker_drawing │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── hector_marker_drawing │ │ │ ├── DrawInterface.h │ │ │ └── HectorDrawings.h │ └── package.xml ├── hector_nav_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── srv │ │ ├── GetDistanceToObstacle.srv │ │ ├── GetNormal.srv │ │ ├── GetRecoveryInfo.srv │ │ ├── GetRobotTrajectory.srv │ │ └── GetSearchPosition.srv ├── hector_slam │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml ├── hector_slam_launch │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── cityflyer_logfile_processing.launch │ │ ├── hector_ugv.launch │ │ ├── height_mapping.launch │ │ ├── mapping_box.launch │ │ ├── mpo700_mapping.launch │ │ ├── postproc_data.launch │ │ ├── postproc_qut_logs.launch │ │ ├── pr2os.launch │ │ └── tutorial.launch │ ├── package.xml │ └── rviz_cfg │ │ └── mapping_demo.rviz └── hector_trajectory_server │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ └── hector_trajectory_server.cpp ├── hokuyo_node ├── CHANGELOG.rst ├── CMakeLists.txt ├── COPYING.lib ├── cfg │ └── Hokuyo.cfg ├── hokuyo_test.launch ├── hokuyo_test.vcg ├── hokuyo_test_intensity.launch ├── include │ └── hokuyo_node │ │ └── hokuyo.h ├── package.xml ├── src │ ├── CMakeLists.txt │ ├── getFirmwareVersion.cpp │ ├── getID.cpp │ ├── hokuyo.cpp │ ├── hokuyo_node.cpp │ └── timestamp_test.cpp └── test │ ├── TODO │ └── unplug_test.launch ├── octomap_mapping ├── .gitignore ├── .travis.yml ├── README.md ├── octomap_mapping │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml └── octomap_server │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ └── octomap_server │ │ ├── OctomapServer.h │ │ ├── OctomapServerMultilayer.h │ │ └── TrackingOctomapServer.h │ ├── launch │ ├── octomap_mapping.launch │ ├── octomap_mapping_nodelet.launch │ ├── octomap_tracking_client.launch │ └── octomap_tracking_server.launch │ ├── mainpage.dox │ ├── nodelet_plugins.xml │ ├── package.xml │ ├── params │ └── default.yaml │ ├── scripts │ └── octomap_eraser_cli.py │ └── src │ ├── OctomapServer.cpp │ ├── OctomapServerMultilayer.cpp │ ├── TrackingOctomapServer.cpp │ ├── octomap_saver.cpp │ ├── octomap_server_multilayer.cpp │ ├── octomap_server_node.cpp │ ├── octomap_server_nodelet.cpp │ ├── octomap_server_static.cpp │ └── octomap_tracking_server_node.cpp ├── scoutrobot_control ├── CMakeLists.txt ├── Launch Commands.txt ├── autonav.py ├── package.xml └── scoutrobot_control.py └── teleop_twist_keyboard ├── CHANGELOG.rst ├── CMakeLists.txt ├── README.md ├── package.xml ├── teleop_twist_keyboard.py └── teleop_twist_keyboard_custom.py /Screenshot 1.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/Screenshot 1.jpg -------------------------------------------------------------------------------- /Screenshot 2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/Screenshot 2.jpg -------------------------------------------------------------------------------- /Screenshot 3.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/Screenshot 3.jpg -------------------------------------------------------------------------------- /ardrone_autonomy/.gitignore: -------------------------------------------------------------------------------- 1 | # Compiled Object files 2 | *.slo 3 | *.lo 4 | *.o 5 | 6 | # Project Files 7 | *.sublime-workspace 8 | *.sublime-project 9 | 10 | # Compiled Dynamic libraries 11 | *.so 12 | 13 | # Compiled Static libraries 14 | *.lai 15 | *.la 16 | *.a 17 | /nbproject/private/ 18 | /build/CMakeFiles/ 19 | 20 | # Build results 21 | /ARDroneLib/FFMPEG/Includes 22 | /ARDroneLib/FFMPEG/FFMPEG 23 | /ARDroneLib/Soft/Build/ 24 | /ARDroneLib/Soft/Common/generated_custom.h 25 | /bin 26 | /build/ 27 | /msg_gen 28 | /srv_gen 29 | /src/ardrone_autonomy 30 | scripts/cache/DEBS_avail 31 | CMakeLists.txt.user 32 | 33 | # Documentations 34 | docs/_build/ 35 | -------------------------------------------------------------------------------- /ardrone_autonomy/.travis.yml: -------------------------------------------------------------------------------- 1 | # Use new TravisCI infrastructure (Ubuntu Trusty) to build the package for both Indigo and Jade 2 | sudo: required 3 | dist: trusty 4 | # Force travis to use its minimal image with default Python settings 5 | language: generic 6 | compiler: 7 | - gcc 8 | env: 9 | global: 10 | - CATKIN_WS=~/catkin_ws 11 | - CATKIN_WS_SRC=${CATKIN_WS}/src 12 | matrix: 13 | - CI_ROS_DISTRO="indigo" 14 | - CI_ROS_DISTRO="jade" 15 | install: 16 | - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu trusty main" > /etc/apt/sources.list.d/ros-latest.list' 17 | - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - 18 | - sudo apt-get update -qq 19 | - sudo apt-get install -qq -y python-rosdep python-catkin-tools 20 | - sudo rosdep init 21 | - rosdep update 22 | # Use rosdep to install all dependencies (including ROS itself) 23 | - rosdep install --from-paths ./ -i -y --rosdistro $CI_ROS_DISTRO 24 | script: 25 | - source /opt/ros/$CI_ROS_DISTRO/setup.bash 26 | - mkdir -p $CATKIN_WS_SRC 27 | - ln -s $TRAVIS_BUILD_DIR $CATKIN_WS_SRC 28 | - cd $CATKIN_WS 29 | - catkin init 30 | # Enable install space 31 | #- catkin config --install 32 | # Build [and Install] packages 33 | - catkin build --limit-status-rate 0.1 --no-notify -DCMAKE_BUILD_TYPE=Release 34 | # Build tests 35 | #- catkin build --limit-status-rate 0.1 --no-notify --make-args tests 36 | # Run tests 37 | #- catkin run_tests 38 | -------------------------------------------------------------------------------- /ardrone_autonomy/LICENSE: -------------------------------------------------------------------------------- 1 | Copyright (c) 2015, Mani Monajjemi 2 | All rights reserved. 3 | 4 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 5 | 6 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 7 | 8 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 9 | 10 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 11 | 12 | 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 FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 13 | -------------------------------------------------------------------------------- /ardrone_autonomy/Makefile: -------------------------------------------------------------------------------- 1 | include $(shell rospack find mk)/cmake.mk -------------------------------------------------------------------------------- /ardrone_autonomy/README.md: -------------------------------------------------------------------------------- 1 | # ardrone_autonomy 2 | 3 | [ROS](http://ros.org) Driver for [Parrot AR-Drone](http://ardrone2.parrot.com/) 1.0 & 2.0 Quadrocopters 4 | 5 | * Documentation: http://ardrone-autonomy.readthedocs.org/ 6 | * ROS wiki page: http://wiki.ros.org/ardrone_autonomy 7 | * Code API: http://docs.ros.org/indigo/api/ardrone_autonomy/html 8 | * Patched _ARDroneLib_ repository: https://github.com/AutonomyLab/ardronelib 9 | * Author: [Mani Monajjemi](http://mani.im) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca)) + [other contributers](http://ardrone-autonomy.readthedocs.org/en/latest/contributers.html) 10 | 11 | ## Build Status 12 | 13 | * ROS Build farm (_Jade_): [![Build Status](http://build.ros.org/buildStatus/icon?job=Jdev__ardrone_autonomy__ubuntu_trusty_amd64)](http://build.ros.org/job/Jdev__ardrone_autonomy__ubuntu_trusty_amd64/) 14 | * ROS Build farm (_Indigo_): [![Build Status](http://build.ros.org/buildStatus/icon?job=Idev__ardrone_autonomy__ubuntu_trusty_amd64)](http://build.ros.org/job/Idev__ardrone_autonomy__ubuntu_trusty_amd64/) 15 | * Travis (_Jade_/_Indigo_): [![Build Status](https://travis-ci.org/AutonomyLab/ardrone_autonomy.svg?branch=indigo-devel)](https://travis-ci.org/AutonomyLab/ardrone_autonomy) 16 | 17 | -------------------------------------------------------------------------------- /ardrone_autonomy/data/camera_info/ardrone_bottom.yaml: -------------------------------------------------------------------------------- 1 | image_width: 640 2 | image_height: 360 3 | camera_name: ardrone_bottom 4 | camera_matrix: 5 | rows: 3 6 | cols: 3 7 | data: [700.490828918144, 0, 319.508832099787, 0, 701.654116650887, 218.740253550967, 0, 0, 1] 8 | distortion_model: plumb_bob 9 | distortion_coefficients: 10 | rows: 1 11 | cols: 5 12 | data: [0.0182389759532889, 0.0520276742502367, 0.00651075732801101, 0.000183496184521575, 0] 13 | rectification_matrix: 14 | rows: 3 15 | cols: 3 16 | data: [1, 0, 0, 0, 1, 0, 0, 0, 1] 17 | projection_matrix: 18 | rows: 3 19 | cols: 4 20 | data: [706.46533203125, 0, 319.100033140348, 0, 0, 704.728332519531, 219.675699140967, 0, 0, 0, 1, 0] -------------------------------------------------------------------------------- /ardrone_autonomy/data/camera_info/ardrone_front.yaml: -------------------------------------------------------------------------------- 1 | image_width: 640 2 | image_height: 360 3 | camera_name: ardrone_front 4 | camera_matrix: 5 | rows: 3 6 | cols: 3 7 | data: [569.883158064802, 0, 331.403348466206, 0, 568.007065238522, 135.879365106014, 0, 0, 1] 8 | distortion_model: plumb_bob 9 | distortion_coefficients: 10 | rows: 1 11 | cols: 5 12 | data: [-0.526629354780687, 0.274357114262035, 0.0211426202132638, -0.0063942451330052, 0] 13 | rectification_matrix: 14 | rows: 3 15 | cols: 3 16 | data: [1, 0, 0, 0, 1, 0, 0, 0, 1] 17 | projection_matrix: 18 | rows: 3 19 | cols: 4 20 | data: [463.275726318359, 0, 328.456687172518, 0, 0, 535.977355957031, 134.693732992726, 0, 0, 0, 1, 0] -------------------------------------------------------------------------------- /ardrone_autonomy/docs/commands.rst: -------------------------------------------------------------------------------- 1 | ============================ 2 | Sending Commands to AR-Drone 3 | ============================ 4 | 5 | The drone will `takeoff`, `land` or `emergency stop/reset` if a ROS `std_msgs/Empty `_ message is published to ``ardrone/takeoff``, ``ardrone/land`` and ``ardrone/reset`` topics respectively. 6 | 7 | In order to fly the drone after takeoff, you can publish a message of type `geometry_msgs::Twist `_ to the ``cmd_vel`` topic:: 8 | 9 | 10 | -linear.x: move backward 11 | +linear.x: move forward 12 | -linear.y: move right 13 | +linear.y: move left 14 | -linear.z: move down 15 | +linear.z: move up 16 | 17 | -angular.z: turn right 18 | +angular.z: turn left 19 | 20 | The range for each component should be between -1.0 and 1.0. The maximum range can be configured using ROS Parameters_ discussed later in this document. 21 | 22 | Hover Modes 23 | ----------- 24 | 25 | ``geometry_msgs::Twist`` has two other member variables ``angular.x`` and ``angular.y`` which can be used to enable/disable "auto-hover" mode. "auto-hover" is enabled when all six components are set to **zero**. If you want the drone not to enter "auto hover" mode in cases you set the first four components to zero, set `angular.x` and `angular.y` to arbitrary **non-zero** values. 26 | 27 | 28 | -------------------------------------------------------------------------------- /ardrone_autonomy/docs/frames.rst: -------------------------------------------------------------------------------- 1 | ================= 2 | Coordinate frames 3 | ================= 4 | 5 | The driver publishes three `TF `_ transforms between these frames: ``odom``, ``${base_prefix}_link``, ``${base_prefix}_frontcam`` and ``${tf_prefix}/${base_prefix}_bottomcam``. The `${base_link}` is the shared name prefix of all three reference frames and can also be set using :doc:`parameters`, by default it has the value of `ardrone_base`. 6 | 7 | .. image:: images/frames.jpg 8 | 9 | The `frame_id` field in header of all published topics (navdata, imu, cameras) will have the appropriate frame names. All frames are `ROS REP 103 `_ compatible. 10 | -------------------------------------------------------------------------------- /ardrone_autonomy/docs/images/frames.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_autonomy/docs/images/frames.jpg -------------------------------------------------------------------------------- /ardrone_autonomy/docs/installation.rst: -------------------------------------------------------------------------------- 1 | ============ 2 | Installation 3 | ============ 4 | 5 | Binary install 6 | ============== 7 | 8 | On supported *Ubuntu* platform and for ROS *Indigo*, *Hydro* and *Groovy* you can install the driver by running ``apt-get install ros-*-ardrone-autonomy`` e.g. ``apt-get install ros-hydro-ardrone-autonomy`` in a terminal. 9 | 10 | Compile from source 11 | =============================== 12 | 13 | The bundled AR-Drone SDK has its own build system which usually handles system wide dependencies itself. The ROS package depends on these standard ROS packages: ``roscpp``, ``image_transport``, ``sensor_msgs``, ``tf``, ``camera_info_manager``, `nav_msgs` and ``std_srvs``. 14 | 15 | The installation follows the same steps needed usually to compile a ROS driver using `catkin `. Clone (or download and unpack) the driver to the ``src`` folder of a new or existing catkin `workspace ` (e.g ``~/catkin_ws/src``), then run ``catkin_make`` to compile it. Assuming you are compiling for ROS *Indigo*: 16 | 17 | .. code-block:: bash 18 | 19 | $ cd ~/catkin_ws/src 20 | $ git clone https://github.com/AutonomyLab/ardrone_autonomy.git -b indigo-devel 21 | $ cd ~/catkin_ws 22 | $ rosdep install --from-paths src -i 23 | $ catkin_make 24 | 25 | -------------------------------------------------------------------------------- /ardrone_autonomy/docs/license.rst: -------------------------------------------------------------------------------- 1 | ======= 2 | License 3 | ======= 4 | 5 | - `The Parrot's license, copyright and disclaimer for ARDroneLib `_ 6 | 7 | - Other parts of the code are subject to `BSD license `_ 8 | -------------------------------------------------------------------------------- /ardrone_autonomy/docs/run.rst: -------------------------------------------------------------------------------- 1 | ================== 2 | Running the driver 3 | ================== 4 | 5 | The driver's executable node is ``ardrone_driver``. You can either run ``rosrun ardrone_autonomy ardrone_driver`` directly or use a custom launch file with your desired parameters. Example launch files are located in the ``launch`` directory. 6 | 7 | -------------------------------------------------------------------------------- /ardrone_autonomy/docs/usage.rst: -------------------------------------------------------------------------------- 1 | ================== 2 | Usage 3 | ================== 4 | 5 | The driver's executable node is ``ardrone_driver``. You can either run ``rosrun ardrone_autonomy ardrone_driver`` directly or use a custom launch file with your desired parameters. Example launch files are located in the ``launch`` directory. 6 | 7 | -------------------------------------------------------------------------------- /ardrone_autonomy/launch/ardrone.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | [0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1] 30 | [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] 31 | [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 100000.0] 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /ardrone_autonomy/launch/ardrone_group.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /ardrone_autonomy/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b ardrone_autonomy is ... 6 | 7 | 10 | 11 | 12 | \section codeapi Code API 13 | 14 | 24 | 25 | 26 | */ 27 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/Navdata.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Navdata including the ARDrone 2 specifica sensors 4 | # (magnetometer, barometer) 5 | 6 | # 0 means no battery, 100 means full battery 7 | float32 batteryPercent 8 | 9 | # 0: Unknown, 1: Init, 2: Landed, 3: Flying, 4: Hovering, 5: Test 10 | # 6: Taking off, 7: Goto Fix Point, 8: Landing, 9: Looping 11 | # Note: 3,7 seems to discriminate type of flying (isFly = 3 | 7) 12 | uint32 state 13 | 14 | int32 magX 15 | int32 magY 16 | int32 magZ 17 | 18 | # pressure sensor 19 | int32 pressure 20 | 21 | # apparently, there was a temperature sensor added as well. 22 | int32 temp 23 | 24 | # wind sensing... 25 | float32 wind_speed 26 | float32 wind_angle 27 | float32 wind_comp_angle 28 | 29 | # left/right tilt in degrees (rotation about the X axis) 30 | float32 rotX 31 | 32 | # forward/backward tilt in degrees (rotation about the Y axis) 33 | float32 rotY 34 | 35 | # orientation in degrees (rotation about the Z axis) 36 | float32 rotZ 37 | 38 | # estimated altitude (cm) 39 | int32 altd 40 | 41 | # linear velocity (mm/sec) 42 | float32 vx 43 | 44 | # linear velocity (mm/sec) 45 | float32 vy 46 | 47 | # linear velocity (mm/sec) 48 | float32 vz 49 | 50 | #linear accelerations (unit: g) 51 | float32 ax 52 | float32 ay 53 | float32 az 54 | 55 | #motor commands (unit 0 to 255) 56 | uint8 motor1 57 | uint8 motor2 58 | uint8 motor3 59 | uint8 motor4 60 | 61 | #Tags in Vision Detectoion 62 | uint32 tags_count 63 | uint32[] tags_type 64 | uint32[] tags_xc 65 | uint32[] tags_yc 66 | uint32[] tags_width 67 | uint32[] tags_height 68 | float32[] tags_orientation 69 | float32[] tags_distance 70 | 71 | #time stamp 72 | float32 tm 73 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/matrix33.msg: -------------------------------------------------------------------------------- 1 | float32 m11 2 | float32 m12 3 | float32 m13 4 | float32 m21 5 | float32 m22 6 | float32 m23 7 | float32 m31 8 | float32 m32 9 | float32 m33 -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_adc_data_frame.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint32 version 6 | uint8[] data_frame 7 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_altitude.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | int32 altitude_vision 6 | float32 altitude_vz 7 | int32 altitude_ref 8 | int32 altitude_raw 9 | float32 obs_accZ 10 | float32 obs_alt 11 | vector31 obs_x 12 | uint32 obs_state 13 | vector21 est_vb 14 | uint32 est_state 15 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_demo.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint32 ctrl_state 6 | uint32 vbat_flying_percentage 7 | float32 theta 8 | float32 phi 9 | float32 psi 10 | int32 altitude 11 | float32 vx 12 | float32 vy 13 | float32 vz 14 | uint32 num_frames 15 | uint32 detection_camera_type 16 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_euler_angles.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32 theta_a 6 | float32 phi_a 7 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_games.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint32 double_tap_counter 6 | uint32 finish_line_counter 7 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_gyros_offsets.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32[] offset_g 6 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_hdvideo_stream.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint32 hdvideo_state 6 | uint32 storage_fifo_nb_packets 7 | uint32 storage_fifo_size 8 | uint32 usbkey_size 9 | uint32 usbkey_freespace 10 | uint32 frame_number 11 | uint32 usbkey_remaining_time 12 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_kalman_pressure.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32 offset_pressure 6 | float32 est_z 7 | float32 est_zdot 8 | float32 est_bias_PWM 9 | float32 est_biais_pression 10 | float32 offset_US 11 | float32 prediction_US 12 | float32 cov_alt 13 | float32 cov_PWM 14 | float32 cov_vitesse 15 | int32 bool_effet_sol 16 | float32 somme_inno 17 | int32 flag_rejet_US 18 | float32 u_multisinus 19 | float32 gaz_altitude 20 | int32 Flag_multisinus 21 | int32 Flag_multisinus_debut 22 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_magneto.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | int16 mx 6 | int16 my 7 | int16 mz 8 | vector31 magneto_raw 9 | vector31 magneto_rectified 10 | vector31 magneto_offset 11 | float32 heading_unwrapped 12 | float32 heading_gyro_unwrapped 13 | float32 heading_fusion_unwrapped 14 | uint8 magneto_calibration_ok 15 | uint32 magneto_state 16 | float32 magneto_radius 17 | float32 error_mean 18 | float32 error_var 19 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_phys_measures.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32 accs_temp 6 | uint16 gyro_temp 7 | float32[] phys_accs 8 | float32[] phys_gyros 9 | uint32 alim3V3 10 | uint32 vrefEpson 11 | uint32 vrefIDG 12 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_pressure_raw.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | int32 up 6 | int16 ut 7 | int32 Temperature_meas 8 | int32 Pression_meas 9 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_pwm.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint8 motor1 6 | uint8 motor2 7 | uint8 motor3 8 | uint8 motor4 9 | uint8 sat_motor1 10 | uint8 sat_motor2 11 | uint8 sat_motor3 12 | uint8 sat_motor4 13 | float32 gaz_feed_forward 14 | float32 gaz_altitude 15 | float32 altitude_integral 16 | float32 vz_ref 17 | int32 u_pitch 18 | int32 u_roll 19 | int32 u_yaw 20 | float32 yaw_u_I 21 | int32 u_pitch_planif 22 | int32 u_roll_planif 23 | int32 u_yaw_planif 24 | float32 u_gaz_planif 25 | uint16 current_motor1 26 | uint16 current_motor2 27 | uint16 current_motor3 28 | uint16 current_motor4 29 | float32 altitude_der 30 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_raw_measures.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | int16[] raw_gyros 6 | int16[] raw_gyros_110 7 | uint32 vbat_raw 8 | uint16 us_debut_echo 9 | uint16 us_fin_echo 10 | uint16 us_association_echo 11 | uint16 us_distance_echo 12 | uint16 us_courbe_temps 13 | uint16 us_courbe_valeur 14 | uint16 us_courbe_ref 15 | uint16 flag_echo_ini 16 | uint16 nb_echo 17 | uint32 sum_echo 18 | int32 alt_temp_raw 19 | int16 gradient 20 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_rc_references.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | int32 rc_ref_pitch 6 | int32 rc_ref_roll 7 | int32 rc_ref_yaw 8 | int32 rc_ref_gaz 9 | int32 rc_ref_ag 10 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_references.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | int32 ref_theta 6 | int32 ref_phi 7 | int32 ref_theta_I 8 | int32 ref_phi_I 9 | int32 ref_pitch 10 | int32 ref_roll 11 | int32 ref_yaw 12 | int32 ref_psi 13 | float32 vx_ref 14 | float32 vy_ref 15 | float32 theta_mod 16 | float32 phi_mod 17 | float32 k_v_x 18 | float32 k_v_y 19 | uint32 k_mode 20 | float32 ui_time 21 | float32 ui_theta 22 | float32 ui_phi 23 | float32 ui_psi 24 | float32 ui_psi_accuracy 25 | int32 ui_seq 26 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_time.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint32 time 6 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_trackers_send.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | int32[] locked 6 | vector21[] point 7 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_trims.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32 angular_rates_trim_r 6 | float32 euler_angles_trim_theta 7 | float32 euler_angles_trim_phi 8 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_video_stream.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint8 quant 6 | uint32 frame_size 7 | uint32 frame_number 8 | uint32 atcmd_ref_seq 9 | uint32 atcmd_mean_ref_gap 10 | float32 atcmd_var_ref_gap 11 | uint32 atcmd_ref_quality 12 | uint32 desired_bitrate 13 | int32 data2 14 | int32 data3 15 | int32 data4 16 | int32 data5 17 | uint32 fifo_queue_level 18 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_vision.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint32 vision_state 6 | int32 vision_misc 7 | float32 vision_phi_trim 8 | float32 vision_phi_ref_prop 9 | float32 vision_theta_trim 10 | float32 vision_theta_ref_prop 11 | int32 new_raw_picture 12 | float32 theta_capture 13 | float32 phi_capture 14 | float32 psi_capture 15 | int32 altitude_capture 16 | uint32 time_capture 17 | vector31 body_v 18 | float32 delta_phi 19 | float32 delta_theta 20 | float32 delta_psi 21 | uint32 gold_defined 22 | uint32 gold_reset 23 | float32 gold_x 24 | float32 gold_y 25 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_vision_detect.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint32 nb_detected 6 | uint32[] type 7 | uint32[] xc 8 | uint32[] yc 9 | uint32[] width 10 | uint32[] height 11 | uint32[] dist 12 | float32[] orientation_angle 13 | matrix33[] rotation 14 | vector31[] translation 15 | uint32[] camera_source 16 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_vision_of.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32[] of_dx 6 | float32[] of_dy 7 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_vision_perf.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32 time_corners 6 | float32 time_compute 7 | float32 time_tracking 8 | float32 time_trans 9 | float32 time_update 10 | float32[] time_custom 11 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_vision_raw.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32 vision_tx_raw 6 | float32 vision_ty_raw 7 | float32 vision_tz_raw 8 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_watchdog.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_wifi.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | uint32 link_quality 6 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_wind_speed.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | float32 wind_speed 6 | float32 wind_angle 7 | float32 wind_compensation_theta 8 | float32 wind_compensation_phi 9 | float32 state_x1 10 | float32 state_x2 11 | float32 state_x3 12 | float32 state_x4 13 | float32 state_x5 14 | float32 state_x6 15 | float32 magneto_debug1 16 | float32 magneto_debug2 17 | float32 magneto_debug3 18 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/navdata_zimmu_3000.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 drone_time 3 | uint16 tag 4 | uint16 size 5 | int32 vzimmuLSB 6 | float32 vzfind 7 | -------------------------------------------------------------------------------- /ardrone_autonomy/msg/vector21.msg: -------------------------------------------------------------------------------- 1 | float32 x 2 | float32 y -------------------------------------------------------------------------------- /ardrone_autonomy/msg/vector31.msg: -------------------------------------------------------------------------------- 1 | float32 x 2 | float32 y 3 | float32 z -------------------------------------------------------------------------------- /ardrone_autonomy/package.xml: -------------------------------------------------------------------------------- 1 | 2 | ardrone_autonomy 3 | 1.4.1 4 | ardrone_autonomy is a ROS driver for Parrot AR-Drone 1.0 and 2.0 quadrocopters. This driver is based on official AR-Drone SDK version 2.0.1. 5 | 6 | Mani Monajjemi 7 | Mani Monajjemi 8 | 9 | BSD 10 | 11 | http://wiki.ros.org/ardrone_autonomy 12 | https://github.com/AutonomyLab/ardrone_autonomy/issues 13 | 14 | Mani Monajjemi 15 | 16 | 17 | catkin 18 | 19 | 20 | 21 | binutils 22 | daemontools 23 | sdl 24 | gtk2 25 | libxml2 26 | libudev-dev 27 | libiw-dev 28 | git 29 | 30 | 31 | roscpp 32 | image_transport 33 | sensor_msgs 34 | std_srvs 35 | tf 36 | camera_info_manager 37 | message_generation 38 | nav_msgs 39 | roslint 40 | 41 | 42 | roscpp 43 | image_transport 44 | sensor_msgs 45 | std_srvs 46 | tf 47 | camera_info_manager 48 | message_runtime 49 | nav_msgs 50 | 51 | 52 | 53 | 54 | 55 | 56 | -------------------------------------------------------------------------------- /ardrone_autonomy/rosdep.yaml: -------------------------------------------------------------------------------- 1 | libsdl-dev: 2 | ubuntu: libsdl1.2-dev 3 | -------------------------------------------------------------------------------- /ardrone_autonomy/rosdoc.yaml: -------------------------------------------------------------------------------- 1 | - builder: doxygen 2 | name: C++ API 3 | output_dir: c++ 4 | file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox' 5 | exclude_patterns: '*/ARDroneLib/*' 6 | -------------------------------------------------------------------------------- /ardrone_autonomy/scripts/README.md: -------------------------------------------------------------------------------- 1 | The files in this folder are the under-the-hood scripts to generate full navdata messages and init/publish routines. There is no need to change/execute these files unless you know exactly what you are doing. 2 | -------------------------------------------------------------------------------- /ardrone_autonomy/srv/CamSelect.srv: -------------------------------------------------------------------------------- 1 | uint8 channel 2 | --- 3 | bool result 4 | -------------------------------------------------------------------------------- /ardrone_autonomy/srv/FlightAnim.srv: -------------------------------------------------------------------------------- 1 | # 0 : ARDRONE_ANIM_PHI_M30_DEG 2 | # 1 : ARDRONE_ANIM_PHI_30_DEG 3 | # 2 : ARDRONE_ANIM_THETA_M30_DEG 4 | # 3 : ARDRONE_ANIM_THETA_30_DEG 5 | # 4 : ARDRONE_ANIM_THETA_20DEG_YAW_200DEG 6 | # 5 : ARDRONE_ANIM_THETA_20DEG_YAW_M200DEG 7 | # 6 : ARDRONE_ANIM_TURNAROUND 8 | # 7 : ARDRONE_ANIM_TURNAROUND_GODOWN 9 | # 8 : ARDRONE_ANIM_YAW_SHAKE 10 | # 9 : ARDRONE_ANIM_YAW_DANCE 11 | # 10: ARDRONE_ANIM_PHI_DANCE 12 | # 11: ARDRONE_ANIM_THETA_DANCE 13 | # 12: ARDRONE_ANIM_VZ_DANCE 14 | # 13: ARDRONE_ANIM_WAVE 15 | # 14: ARDRONE_ANIM_PHI_THETA_MIXED 16 | # 15: ARDRONE_ANIM_DOUBLE_PHI_THETA_MIXED 17 | # 16: ARDRONE_ANIM_FLIP_AHEAD 18 | # 17: ARDRONE_ANIM_FLIP_BEHIND 19 | # 18: ARDRONE_ANIM_FLIP_LEFT 20 | # 19: ARDRONE_ANIM_FLIP_RIGHT 21 | 22 | uint8 type 23 | 24 | # In Milliseconds 25 | # 0 For Default Duration (Recommended) 26 | uint32 duration 27 | 28 | --- 29 | bool result 30 | 31 | -------------------------------------------------------------------------------- /ardrone_autonomy/srv/LedAnim.srv: -------------------------------------------------------------------------------- 1 | # 0 : BLINK_GREEN_RED 2 | # 1 : BLINK_GREEN 3 | # 2 : BLINK_RED 4 | # 3 : BLINK_ORANGE 5 | # 4 : SNAKE_GREEN_RED 6 | # 5 : FIRE 7 | # 6 : STANDARD 8 | # 7 : RED 9 | # 8 : GREEN 10 | # 9 : RED_SNAKE 11 | # 10: BLANK 12 | # 11: LEFT_GREEN_RIGHT_RED 13 | # 12: LEFT_RED_RIGHT_GREEN 14 | # 13: BLINK_STANDARD 15 | uint8 type 16 | 17 | # In Hz 18 | float32 freq 19 | 20 | # In Seconds 21 | uint8 duration 22 | 23 | --- 24 | bool result 25 | -------------------------------------------------------------------------------- /ardrone_autonomy/srv/RecordEnable.srv: -------------------------------------------------------------------------------- 1 | bool enable 2 | --- 3 | bool result -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/README.md: -------------------------------------------------------------------------------- 1 | tum_simulator on Indigo and Gazebo 7 2 | ============= 3 | 4 | These packages are used to simulate the flying robot Ardrone in ROS environment using gazebo simulator. Totally they are 4 packages. Their functions are descript as below: 5 | 6 | 1. cvg_sim_gazebo: contains object models, sensor models, quadrocopter models, flying environment information and individual launch files for each objects and pure environment without any other objects. 7 | 8 | 2. cvg_sim_gazebo_plugins: contains gazebo plugins for the quadrocopter model. quadrotor_simple_controller is used to control the robot motion and deliver navigation information, such as: /ardrone/navdata. Others are plugins for sensors in the quadrocopter, such as: IMU sensor, sonar sensor, GPS sensor. 9 | 10 | 3. message_to_tf: is a package used to create a ros node, which transfers the ros topic /ground_truth/state to a /tf topic. 11 | 12 | 4. cvg_sim_msgs: contains message forms for the simulator. 13 | 14 | Some packages are based on the tu-darmstadt-ros-pkg by Stefan Kohlbrecher, TU Darmstadt. 15 | 16 | This package depends on ardrone_autonomy package and gazebo7 so install these first. 17 | 18 | How to install the simulator: 19 | 20 | 1. Install gazebo7 and ardrone_autonomy package 21 | 22 | 2. Create a workspace for the simulator 23 | 24 | ``` 25 | mkdir -p ~/ardrone_simulator/src 26 | cd ~/ardrone_simulator/src 27 | catkin_init_workspace 28 | ``` 29 | 2. Download package 30 | 31 | ``` 32 | git clone https://github.com/iolyp/ardrone_simulator_gazebo7 33 | ``` 34 | 3. Build the simulator 35 | 36 | ``` 37 | cd .. 38 | catkin_make 39 | ``` 40 | 4. Source the environment 41 | 42 | ``` 43 | source devel/setup.bash 44 | ``` 45 | How to run a simulation: 46 | 47 | 1. Run a simulation by executing a launch file in cvg_sim_gazebo package: 48 | 49 | ``` 50 | roslaunch cvg_sim_gazebo ardrone_testworld.launch 51 | ``` 52 | 53 | How to run a simulation using ar_track_alvar tags: 54 | 55 | 1. Move the contents of ~/ardrone_simulator/src/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ to ~/.gazebo/models 56 | 57 | 2. Run simulation 58 | 59 | ``` 60 | roslaunch cvg_sim_gazebo ar_tag.launch 61 | ``` -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/launch/ar_tag.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/launch/empty_world.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/launch/scoutrobot.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/launch/scoutrobot_world_1.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/launch/scoutrobot_world_2.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/launch/scoutrobot_world_3.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/launch/spawn_quadrotor.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/launch/spawn_quadrotor_2.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag0/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag0/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag0/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 0 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 0 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag0/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag0/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag0/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag1/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag1/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag1/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 1 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 1 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag1/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag1/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag1/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag2/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag2/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag2/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 2 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 2 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag2/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag2/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag2/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag3/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag3/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag3/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 3 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 3 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag3/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag3/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag3/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag4/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag4/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag4/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 4 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 4 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag4/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag4/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag4/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag5/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag5/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag5/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 5 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 5 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag5/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag5/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag5/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag6/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag6/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag6/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 6 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 6 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag6/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag6/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag6/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag7/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag7/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag7/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 7 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 7 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag7/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag7/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag7/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag8/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag8/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag8/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 8 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 8 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag8/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag8/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag8/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag9/meshes/MarkerData_0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag9/meshes/MarkerData_0.png -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag9/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ar tag 9 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Ioannis Lypiridis 10 | iolypiridis@gmail.com 11 | 12 | 13 | 14 | Ar tag 9 for alvar 20cm. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/ar_track_alvar_tags/ar_alvar_tag9/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://ar_alvar_tag9/meshes/artag.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://ar_alvar_tag9/meshes/artag.dae 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/hokuyo_utm30lx/blender/hokuyo_utm30lx.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/hokuyo_utm30lx/blender/hokuyo_utm30lx.blend -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.stl -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/kinect_camera/kinect_camera_simple.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/kinect_camera/kinect_camera_simple.stl -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_2.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_2.blend -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_2.blend1: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_2.blend1 -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_3.blend1: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_3.blend1 -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_CAD.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_CAD.blend -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_CAD2.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_CAD2.blend -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_CAD2.blend1: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_CAD2.blend1 -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_CAD2.blend2: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_CAD2.blend2 -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_base.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/blender/quadrotor_base.blend -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/quadrotor_2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/quadrotor_2.stl -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/quadrotor_3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/quadrotor_3.stl -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/quadrotor_4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/quadrotor_4.stl -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/quadrotor_base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/quadrotor/quadrotor_base.stl -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/sonar_sensor/blender/max_sonar_ez4.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/sonar_sensor/blender/max_sonar_ez4.blend -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/thermaleye_camera/thermaleye_camera_hector_v1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/thermaleye_camera/thermaleye_camera_hector_v1.stl -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/thermaleye_camera/thermaleye_camera_hector_v2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/meshes/thermaleye_camera/thermaleye_camera_hector_v2.stl -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | cvg_sim_gazebo 4 | 0.0.0 5 | The cvg_sim_gazebo package 6 | 7 | 8 | 9 | 10 | elliot 11 | 12 | 13 | 14 | 15 | 16 | TODO 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | catkin 43 | gazebo_ros 44 | gazebo_ros 45 | cvg_sim_gazebo_plugins 46 | 47 | 48 | 49 | 50 | 51 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/urdf/moveit_demo.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/ardrone_simulator_gazebo7/cvg_sim_gazebo/urdf/moveit_demo.urdf.xacro -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/urdf/quadrotor.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/urdf/quadrotor_base.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | false 51 | 52 | 53 | 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/urdf/quadrotor_base.urdf.xacro.original: -------------------------------------------------------------------------------- 1 | 2 | 3 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | false 40 | 41 | 42 | 43 | 44 | 45 | 46 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo/urdf/velodyne_definition: -------------------------------------------------------------------------------- 1 | 2 | 3 | 0.0 0.0 0.0 0.0 0 0 4 | true 5 | 10 6 | 7 | 8 | 9 | 720 10 | -0.785 11 | 0.785 12 | 13 | 14 | 16 15 | -0.26 16 | 0.26 17 | 18 | 19 | 20 | 0.30 21 | 100.0 22 | 23 | 24 | 25 | /velodyne_laser 26 | velodyne_laser 27 | true 28 | 0.00 29 | 10.0 30 | 1 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo_plugins/src/cvg_sim_gazebo_plugins/__init__.py: -------------------------------------------------------------------------------- 1 | #autogenerated by ROS python message generators -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo_plugins/srv/SetBias.srv: -------------------------------------------------------------------------------- 1 | geometry_msgs/Vector3 bias 2 | --- 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo_plugins/urdf/quadrotor_plugins.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | base_link 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_gazebo_plugins/urdf/quadrotor_simple_controller.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 7 | 8 | 9 | 10 | 11 | 12 | true 13 | 0.0 14 | base_link 15 | ground_truth/state 16 | ardrone/imu 17 | cmd_vel 18 | 10.0 19 | 5.0 20 | 0.5 21 | 2.0 22 | 1.0 23 | 1.5 24 | 5.0 25 | 1.0 26 | 2 27 | 5.0 28 | 1.0 29 | 0.5 30 | 30 31 | 0.05 32 | 0.03 33 | 5.0 34 | 35 | 36 | 37 | true 38 | 0.0 39 | base_link 40 | ground_truth/state 41 | ardrone/imu 42 | sonar_height 43 | cmd_vel 44 | 45 | 46 | 47 | 48 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/Altimeter.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 altitude 3 | float32 pressure 4 | float32 qnh 5 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/Altitude.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 height 3 | float32 altitude 4 | float32 elevation 5 | float32 qnh 6 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/AttitudeCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 roll 3 | float32 pitch 4 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/Compass.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 magnetic_heading 3 | float32 declination 4 | 5 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/ControllerState.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint8 source 3 | 4 | uint8 mode 5 | uint8 MOTORS = 1 6 | uint8 ATTITUDE = 2 7 | uint8 VELOCITY = 4 8 | uint8 POSITION = 8 9 | uint8 HEADING = 16 10 | uint8 HEIGHT = 32 11 | 12 | uint8 state 13 | uint8 MOTORS_RUNNING = 1 14 | uint8 AIRBORNE = 2 15 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/HeadingCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 heading 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/HeightCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 height 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/MotorCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32[] force 3 | float32[] torque 4 | float32[] frequency 5 | float32[] voltage 6 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/MotorPWM.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint8[] pwm 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/MotorStatus.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | bool on 3 | bool running 4 | float32[] frequency 5 | uint8[] current 6 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/PositionXYCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 x 3 | float32 y 4 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/RC.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | uint8 ROLL = 1 4 | uint8 PITCH = 2 5 | uint8 YAW = 3 6 | uint8 STEER = 4 7 | uint8 HEIGHT = 5 8 | uint8 THRUST = 6 9 | uint8 BRAKE = 7 10 | 11 | uint8 status 12 | bool valid 13 | 14 | float32[] axis 15 | uint8[] axis_function 16 | 17 | int8[] swit 18 | uint8[] swit_function 19 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/RawImu.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint16[3] angular_velocity 3 | uint16[3] linear_acceleration 4 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/RawMagnetic.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64[3] channel 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/RawRC.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint8 status 3 | uint16[] channel 4 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/RuddersCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 aileron 3 | float32 elevator 4 | float32 rudder 5 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/ServoCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint16[] value 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/Supply.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32[] voltage 3 | float32[] current 4 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/ThrustCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 thrust 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/VelocityXYCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 x 3 | float32 y 4 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/VelocityZCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 z 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/msg/YawrateCommand.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float32 turnrate 3 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | cvg_sim_msgs 4 | 0.0.0 5 | 6 | cvg_sim_msgs contains message form for cvg_sim_gazebo_plugins. 7 | This package is based on hector_uav_msgs by Stefan Kohlbrecher, TU Darmstadt. 8 | 9 | elliot 10 | TODO 11 | 12 | catkin 13 | geometry_msgs 14 | message_generation 15 | message_runtime 16 | geometry_msgs 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/cvg_sim_msgs/src/cvg_sim_msgs/__init__.py: -------------------------------------------------------------------------------- 1 | #autogenerated by ROS python message generators -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/message_to_tf/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | message_to_tf 4 | 0.0.0 5 | The message_to_tf package 6 | Elliot 7 | BSD 8 | 9 | 10 | catkin 11 | geometry_msgs 12 | nav_msgs 13 | sensor_msgs 14 | tf 15 | 16 | geometry_msgs 17 | nav_msgs 18 | sensor_msgs 19 | tf 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/tum_simulator/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(tum_simulator) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /ardrone_simulator_gazebo7/tum_simulator/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | tum_simulator 4 | 0.0.0 5 | The tum_simulator 6 | Elliot 7 | BSD 8 | catkin 9 | cvg_sim_msgs 10 | cvg_sim_gazebo 11 | cvg_sim_gazebo_plugins 12 | message_to_tf 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /driver_common/driver_base/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html 2 | cmake_minimum_required(VERSION 2.8.3) 3 | project(driver_base) 4 | 5 | # Load catkin and all dependencies required for this package 6 | find_package(catkin REQUIRED message_generation std_msgs) 7 | find_package(Boost REQUIRED) 8 | 9 | include_directories(include) 10 | 11 | add_message_files( 12 | DIRECTORY msg 13 | FILES 14 | ConfigString.msg 15 | ConfigValue.msg 16 | SensorLevels.msg) 17 | 18 | generate_messages(DEPENDENCIES std_msgs) 19 | 20 | catkin_package( 21 | INCLUDE_DIRS include 22 | CATKIN_DEPENDS message_runtime std_msgs 23 | DEPENDS Boost) 24 | 25 | install(DIRECTORY include/${PROJECT_NAME}/ 26 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 27 | FILES_MATCHING PATTERN "*.h") -------------------------------------------------------------------------------- /driver_common/driver_base/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | This package's API is not yet released. It may change significantly from 6 | its current form. 7 | 8 | */ 9 | -------------------------------------------------------------------------------- /driver_common/driver_base/msg/ConfigString.msg: -------------------------------------------------------------------------------- 1 | string name 2 | string value 3 | -------------------------------------------------------------------------------- /driver_common/driver_base/msg/ConfigValue.msg: -------------------------------------------------------------------------------- 1 | string name 2 | float64 value 3 | -------------------------------------------------------------------------------- /driver_common/driver_base/msg/SensorLevels.msg: -------------------------------------------------------------------------------- 1 | byte RECONFIGURE_CLOSE = 3 # Parameters that need a sensor to be stopped completely when changed 2 | byte RECONFIGURE_STOP = 1 # Parameters that need a sensor to stop streaming when changed 3 | byte RECONFIGURE_RUNNING = 0 # Parameters that can be changed while a sensor is streaming 4 | -------------------------------------------------------------------------------- /driver_common/driver_base/package.xml: -------------------------------------------------------------------------------- 1 | 2 | driver_base 3 | 1.6.8 4 | A framework for writing drivers that helps with runtime reconfiguration, diagnostics and self-test. 5 | 6 | This package is deprecated. 7 | Chad Rockey 8 | 9 | BSD 10 | 11 | http://www.ros.org/wiki/driver_base 12 | https://github.com/ros-drivers/driver_common/issues 13 | https://github.com/ros-drivers/driver_common 14 | 15 | Blaise Gassend 16 | 17 | catkin 18 | 19 | message_generation 20 | roscpp 21 | self_test 22 | diagnostic_updater 23 | dynamic_reconfigure 24 | std_msgs 25 | 26 | message_runtime 27 | roscpp 28 | self_test 29 | diagnostic_updater 30 | dynamic_reconfigure 31 | std_msgs 32 | 33 | -------------------------------------------------------------------------------- /driver_common/driver_common/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package driver_common 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.6.8 (2014-03-30) 6 | ------------------ 7 | 8 | 1.6.7 (2013-08-21) 9 | ------------------ 10 | * No more Willow Garage email. 11 | * Contributors: Chad Rockey 12 | 13 | 1.6.6 (2013-05-06) 14 | ------------------ 15 | * Updated metapackage for REP 127 16 | * Contributors: chadrockey 17 | 18 | 1.6.5 (2013-01-22) 19 | ------------------ 20 | 21 | 1.6.4 (2012-12-14) 22 | ------------------ 23 | 24 | 1.6.3 (2012-12-13) 25 | ------------------ 26 | 27 | 1.6.2 (2012-12-10) 28 | ------------------ 29 | * Version 1.6.2 30 | * Contributors: William Woodall 31 | 32 | 1.6.1 (2012-12-07 16:02) 33 | ------------------------ 34 | * added metapackage for former stack 35 | * Contributors: Dirk Thomas 36 | 37 | 1.6.0 (2012-12-07 11:00) 38 | ------------------------ 39 | -------------------------------------------------------------------------------- /driver_common/driver_common/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(driver_common) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /driver_common/driver_common/package.xml: -------------------------------------------------------------------------------- 1 | 2 | driver_common 3 | 1.6.8 4 | 5 | The driver_common stack contains classes and tools that are useful 6 | throughout the driver stacks. It currently contains: 7 | 8 | driver_base: A base class for sensors to provide a consistent state machine 9 | (retries, error handling, etc.) and interface 10 | 11 | timestamp_tools: Classes to help timestamp hardware events 12 | 13 | Chad Rockey 14 | BSD 15 | 16 | http://www.ros.org/wiki/driver_common 17 | https://github.com/ros-drivers/driver_common/issues 18 | https://github.com/ros-drivers/driver_common 19 | 20 | Blaise Gassend 21 | 22 | catkin 23 | 24 | driver_base 25 | timestamp_tools 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /driver_common/timestamp_tools/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html 2 | cmake_minimum_required(VERSION 2.8.3) 3 | project(timestamp_tools) 4 | 5 | # Load catkin and all dependencies required for this package 6 | find_package(catkin REQUIRED roslib roscpp) 7 | find_package(Boost REQUIRED) 8 | 9 | include_directories(include) 10 | 11 | catkin_package( 12 | DEPENDS roslib roscpp 13 | INCLUDE_DIRS include 14 | ) 15 | 16 | install(DIRECTORY include/${PROJECT_NAME}/ 17 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 18 | FILES_MATCHING PATTERN "*.h") 19 | 20 | 21 | if(CATKIN_ENABLE_TESTING) 22 | catkin_add_gtest(test_trigger_matcher test/test_trigger_matcher.cpp) 23 | target_link_libraries(test_trigger_matcher ${catkin_LIBRARIES}) 24 | endif() 25 | -------------------------------------------------------------------------------- /driver_common/timestamp_tools/include/timestamp_tools/periodic_timestamp_min_filter.h: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2009-2010, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of the Willow Garage nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | #ifndef __TIMESTAMP_TOOLS__PERIODIC_TIMESTAMP_MIN_FILTER__H__ 36 | #define __TIMESTAMP_TOOLS__PERIODIC_TIMESTAMP_MIN_FILTER__H__ 37 | 38 | namespace timestamp_tools 39 | { 40 | 41 | class PeriodicTimestampMinFilter 42 | { 43 | 44 | }; 45 | 46 | } 47 | 48 | #endif // __TIMESTAMP_TOOLS__PERIODIC_TIMESTAMP_MIN_FILTER__H__ 49 | -------------------------------------------------------------------------------- /driver_common/timestamp_tools/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | This package's API is not yet released. It may change significantly from 6 | its current form. 7 | 8 | */ 9 | -------------------------------------------------------------------------------- /driver_common/timestamp_tools/package.xml: -------------------------------------------------------------------------------- 1 | 2 | timestamp_tools 3 | 1.6.8 4 | This package is currently for internal use only. Its API may change 5 | without warning in the future. This package is deprecated. 6 | Chad Rockey 7 | 8 | BSD 9 | 10 | http://www.ros.org/wiki/timestamp_tools 11 | https://github.com/ros-drivers/driver_common/issues 12 | https://github.com/ros-drivers/driver_common 13 | 14 | Blaise Gassend 15 | 16 | catkin 17 | 18 | roslib 19 | roscpp 20 | 21 | roslib 22 | roscpp 23 | 24 | -------------------------------------------------------------------------------- /hector_models/README.md: -------------------------------------------------------------------------------- 1 | # hector_models 2 | hector_models contains (urdf) models and xacro macros of sensors and robot components. 3 | -------------------------------------------------------------------------------- /hector_models/hector_components_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(hector_components_description) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package( 7 | DEPENDS 8 | CATKIN_DEPENDS 9 | INCLUDE_DIRS 10 | LIBRARIES 11 | ) 12 | 13 | ############# 14 | ## Install ## 15 | ############# 16 | 17 | # all install targets should use catkin DESTINATION variables 18 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 19 | 20 | install(DIRECTORY meshes urdf 21 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 22 | ) 23 | 24 | -------------------------------------------------------------------------------- /hector_models/hector_components_description/meshes/checkerboard/checkerboard.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_components_description/meshes/checkerboard/checkerboard.png -------------------------------------------------------------------------------- /hector_models/hector_components_description/meshes/checkerboard/checkerboard.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_components_description/meshes/checkerboard/checkerboard.stl -------------------------------------------------------------------------------- /hector_models/hector_components_description/meshes/hector_multisensor_head/multisensor_head.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_components_description/meshes/hector_multisensor_head/multisensor_head.stl -------------------------------------------------------------------------------- /hector_models/hector_components_description/meshes/hector_multisensor_head/multisensor_head_collision.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_components_description/meshes/hector_multisensor_head/multisensor_head_collision.stl -------------------------------------------------------------------------------- /hector_models/hector_components_description/meshes/kalibr_targets/april_50x50cm_A0_1024px.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_components_description/meshes/kalibr_targets/april_50x50cm_A0_1024px.png -------------------------------------------------------------------------------- /hector_models/hector_components_description/meshes/vision_box/HectorDarmstadt_TU_Darmstadt_combined_with_background_cut_256.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_components_description/meshes/vision_box/HectorDarmstadt_TU_Darmstadt_combined_with_background_cut_256.png -------------------------------------------------------------------------------- /hector_models/hector_components_description/meshes/vision_box/hector1_top_box.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_components_description/meshes/vision_box/hector1_top_box.stl -------------------------------------------------------------------------------- /hector_models/hector_components_description/meshes/vision_box/hector2_top_box.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_components_description/meshes/vision_box/hector2_top_box.stl -------------------------------------------------------------------------------- /hector_models/hector_components_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | hector_components_description 3 | 0.5.0 4 | hector_components_description contains URDF xacro macros for robot components, so they are easily attachable to robot models. 5 | Stefan Kohlbrecher 6 | 7 | BSD 8 | 9 | http://ros.org/wiki/hector_components_description 10 | 11 | 12 | Stefan Kohlbrecher 13 | 14 | 15 | catkin 16 | 17 | 18 | 19 | 20 | xacro 21 | hector_sensors_description 22 | hector_xacro_tools 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /hector_models/hector_components_description/urdf/checkerboard.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | -------------------------------------------------------------------------------- /hector_models/hector_components_description/urdf/kalibr_april_50x50cm_A0_1024px.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | true 40 | true 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | true 53 | true 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /hector_models/hector_components_description/urdf/spinning_hokuyo_utm30lx.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | -------------------------------------------------------------------------------- /hector_models/hector_components_description/urdf/vision_box_dimensions_hector1.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /hector_models/hector_components_description/urdf/vision_box_dimensions_hector2.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /hector_models/hector_models.rosinstall: -------------------------------------------------------------------------------- 1 | - git: {local-name: src/hector_models, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_models.git', version: hydro-devel} 2 | -------------------------------------------------------------------------------- /hector_models/hector_models/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_models 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.5.0 (2018-06-29) 6 | ------------------ 7 | 8 | 0.4.2 (2016-06-24) 9 | ------------------ 10 | 11 | 0.4.1 (2015-11-08) 12 | ------------------ 13 | 14 | 0.4.0 (2015-11-07) 15 | ------------------ 16 | 17 | 0.3.2 (2014-09-01) 18 | ------------------ 19 | 20 | 0.3.1 (2014-03-30) 21 | ------------------ 22 | * made hector_models a true metapackage 23 | * Moved package hector_sensors_gazebo to ../hector_gazebo 24 | * Contributors: Johannes Meyer 25 | 26 | 0.3.0 (2013-09-02) 27 | ------------------ 28 | * catkinized stack hector_models 29 | -------------------------------------------------------------------------------- /hector_models/hector_models/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(hector_models) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /hector_models/hector_models/package.xml: -------------------------------------------------------------------------------- 1 | 2 | hector_models 3 | 0.5.0 4 | hector_models contains (urdf) models of robots, sensors etc. 5 | Johannes Meyer 6 | 7 | BSD 8 | 9 | http://ros.org/wiki/hector_models 10 | 11 | 12 | Stefan Kohlbrecher 13 | 14 | 15 | catkin 16 | 17 | 18 | hector_sensors_description 19 | hector_xacro_tools 20 | 21 | 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(hector_sensors_description) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package( 7 | DEPENDS 8 | CATKIN_DEPENDS 9 | INCLUDE_DIRS 10 | LIBRARIES 11 | ) 12 | 13 | ############# 14 | ## Install ## 15 | ############# 16 | 17 | # all install targets should use catkin DESTINATION variables 18 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 19 | 20 | install(DIRECTORY meshes urdf 21 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 22 | ) 23 | 24 | -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/meshes/asus_camera/asus_camera_simple.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_sensors_description/meshes/asus_camera/asus_camera_simple.stl -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/meshes/hokuyo_utm30lx/blender/hokuyo_utm30lx.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_sensors_description/meshes/hokuyo_utm30lx/blender/hokuyo_utm30lx.blend -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_sensors_description/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.stl -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/meshes/kinect_camera/kinect_camera_simple.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_sensors_description/meshes/kinect_camera/kinect_camera_simple.stl -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/meshes/sonar_sensor/blender/max_sonar_ez4.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_sensors_description/meshes/sonar_sensor/blender/max_sonar_ez4.blend -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/meshes/thermaleye_camera/thermaleye_camera_hector_v1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_sensors_description/meshes/thermaleye_camera/thermaleye_camera_hector_v1.stl -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/meshes/thermaleye_camera/thermaleye_camera_hector_v2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/abelmeadows/scoutrobot/c7b1efeb9888ee9175148775cce84ac4bb7ce3ab/hector_models/hector_sensors_description/meshes/thermaleye_camera/thermaleye_camera_hector_v2.stl -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | hector_sensors_description 3 | 0.5.0 4 | hector_sensors_description contains URDF xacro macros for sensors, so they are easily attachable to robot models and usable in gazebo. 5 | Johannes Meyer 6 | 7 | BSD 8 | 9 | http://ros.org/wiki/hector_sensors_description 10 | 11 | 12 | Stefan Kohlbrecher 13 | 14 | 15 | catkin 16 | 17 | 18 | 19 | 20 | xacro 21 | 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/urdf/generic_thermal_camera.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 10 21 | 22 | 23 | ${90.0*M_PI/180.0} 24 | 25 | R8G8B8 26 | ${resolution_x} 27 | ${resolution_y} 28 | 29 | 30 | 0.01 31 | 100 32 | 33 | 34 | 35 | 36 | true 37 | 10 38 | /${name}/image_raw 39 | /${name}/camera_info 40 | ${name}_optical_frame 41 | 42 | 43 | 44 | 45 | 46 | 47 | -------------------------------------------------------------------------------- /hector_models/hector_sensors_description/urdf/thermaleye_camera.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | -------------------------------------------------------------------------------- /hector_models/hector_xacro_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_xacro_tools 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.5.0 (2018-06-29) 6 | ------------------ 7 | * Merge branch 'update_transmissions' into kinetic-devel 8 | Fix xmlns for all xacro files 9 | * Update to transmissions, prepending "hardware_interface/" 10 | * fixed warning 11 | * Add macro for default setting joint properties 12 | * Contributors: Alexander Stumpf, Stefan Kohlbrecher 13 | 14 | 0.4.2 (2016-06-24) 15 | ------------------ 16 | * Add joint macros (contains transmission macro for the moment) 17 | * Contributors: Stefan Kohlbrecher 18 | 19 | 0.4.1 (2015-11-08) 20 | ------------------ 21 | * hector_xacro_tools: fixed invalid brackets in inertial_sphere* xacro macros 22 | * Cleaned up root element xmlns arguments according to http://gazebosim.org/tutorials?tut=ros_urdf#HeaderofaURDFFile 23 | * Added missing xacro namespace prefix to XML tags 24 | * Contributors: Johannes Meyer 25 | 26 | 0.4.0 (2015-11-07) 27 | ------------------ 28 | * Remove origin tag as already set via insert block 29 | * Add additional macros 30 | * Contributors: kohlbrecher 31 | 32 | 0.3.2 (2014-09-01) 33 | ------------------ 34 | 35 | 0.3.1 (2014-03-30) 36 | ------------------ 37 | 38 | 0.3.0 (2013-09-02) 39 | ------------------ 40 | * catkinized stack hector_models 41 | -------------------------------------------------------------------------------- /hector_models/hector_xacro_tools/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(hector_xacro_tools) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package( 7 | DEPENDS 8 | CATKIN_DEPENDS 9 | INCLUDE_DIRS 10 | LIBRARIES 11 | ) 12 | 13 | ############# 14 | ## Install ## 15 | ############# 16 | 17 | # all install targets should use catkin DESTINATION variables 18 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 19 | 20 | install(DIRECTORY urdf 21 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 22 | ) 23 | 24 | -------------------------------------------------------------------------------- /hector_models/hector_xacro_tools/package.xml: -------------------------------------------------------------------------------- 1 | 2 | hector_xacro_tools 3 | 0.5.0 4 | hector_xacro_tools 5 | Johannes Meyer 6 | 7 | BSD 8 | 9 | http://ros.org/wiki/hector_xacro_tools 10 | 11 | 12 | Stefan Kohlbrecher 13 | 14 | 15 | catkin 16 | 17 | 18 | 19 | 20 | xacro 21 | 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /hector_models/hector_xacro_tools/urdf/inertia_tensors.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 41 | 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /hector_models/hector_xacro_tools/urdf/joint_macros.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | transmission_interface/SimpleTransmission 8 | 9 | hardware_interface/EffortJointInterface 10 | 11 | 12 | hardware_interface/EffortJointInterface 13 | 1 14 | 15 | 16 | 17 | 1 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /hector_models/hector_xacro_tools/urdf/sensor_macros.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /hector_slam/.gitignore: -------------------------------------------------------------------------------- 1 | bin/ 2 | build/ 3 | lib/ 4 | msg_gen/ 5 | srv_gen/ 6 | hector_mapping/src/hector_mapping/ 7 | hector_nav_msgs/src/hector_nav_msgs/ 8 | -------------------------------------------------------------------------------- /hector_slam/README.txt: -------------------------------------------------------------------------------- 1 | # hector_slam 2 | 3 | See the ROS Wiki for documentation: http://wiki.ros.org/hector_slam 4 | -------------------------------------------------------------------------------- /hector_slam/hector_compressed_map_transport/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_compressed_map_transport 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | * Use the FindEigen3.cmake module provided by Eigen 8 | * Contributors: Johannes Meyer 9 | 10 | 0.3.4 (2015-11-07) 11 | ------------------ 12 | 13 | 0.3.3 (2014-06-15) 14 | ------------------ 15 | * fixed cmake find for eigen in indigo 16 | * fixed libopencv-dev rosdep key 17 | * Contributors: Alexander Stumpf, Johannes Meyer 18 | 19 | 0.3.2 (2014-03-30) 20 | ------------------ 21 | 22 | 0.3.1 (2013-10-09) 23 | ------------------ 24 | * added changelogs 25 | 26 | 0.3.0 (2013-08-08) 27 | ------------------ 28 | * catkinized hector_slam 29 | -------------------------------------------------------------------------------- /hector_slam/hector_geotiff/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_geotiff 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | * Use the FindEigen3.cmake module provided by Eigen 8 | * hector_geotiff/hector_geotiff_plugins: added possibility to specify Color of robot path in the geotiff file in order to allow multiple color robot paths 9 | * Contributors: Dorothea Koert, Johannes Meyer 10 | 11 | 0.3.4 (2015-11-07) 12 | ------------------ 13 | * Removes trailing spaces and fixes indents 14 | * Contributors: YuK_Ota 15 | 16 | 0.3.3 (2014-06-15) 17 | ------------------ 18 | * fixed cmake find for eigen in indigo 19 | * added launchfile to restart geotiff node 20 | * Contributors: Alexander Stumpf 21 | 22 | 0.3.2 (2014-03-30) 23 | ------------------ 24 | * Add TrajectoryMapWriter to geotiff_mapper.launch per default 25 | * Add arguments to launch files for specifying geotiff file path 26 | * Contributors: Stefan Kohlbrecher 27 | 28 | 0.3.1 (2013-10-09) 29 | ------------------ 30 | * added missing install rule for launch files 31 | * moved header files from include/geotiff_writer to include/hector_geotiff 32 | * fixed warnings for deprecated pluginlib method/macro calls 33 | * added changelogs 34 | 35 | 0.3.0 (2013-08-08) 36 | ------------------ 37 | * catkinized hector_slam 38 | -------------------------------------------------------------------------------- /hector_slam/hector_geotiff/include/hector_geotiff/map_writer_plugin_interface.h: -------------------------------------------------------------------------------- 1 | //================================================================================================= 2 | // Copyright (c) 2012, Stefan Kohlbrecher, TU Darmstadt 3 | // All rights reserved. 4 | 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are met: 7 | // * Redistributions of source code must retain the above copyright 8 | // notice, this list of conditions and the following disclaimer. 9 | // * Redistributions in binary form must reproduce the above copyright 10 | // notice, this list of conditions and the following disclaimer in the 11 | // documentation and/or other materials provided with the distribution. 12 | // * Neither the name of the Simulation, Systems Optimization and Robotics 13 | // group, TU Darmstadt nor the names of its contributors may be used to 14 | // endorse or promote products derived from this software without 15 | // specific prior written permission. 16 | 17 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 18 | // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 19 | // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 20 | // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 21 | // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 22 | // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 23 | // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 24 | // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 26 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | //================================================================================================= 28 | 29 | #ifndef _MAPWRITERPLUGININTERFACE_H__ 30 | #define _MAPWRITERPLUGININTERFACE_H__ 31 | 32 | #include "map_writer_interface.h" 33 | 34 | namespace hector_geotiff{ 35 | 36 | class MapWriterPluginInterface{ 37 | 38 | public: 39 | 40 | virtual void initialize(const std::string& name) = 0; 41 | virtual void draw(MapWriterInterface* map_writer_interface) = 0; 42 | 43 | }; 44 | 45 | } //namespace hector_geotiff 46 | 47 | #endif 48 | -------------------------------------------------------------------------------- /hector_slam/hector_geotiff/launch/geotiff_mapper.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /hector_slam/hector_geotiff/launch/geotiff_mapper_only.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /hector_slam/hector_geotiff_plugins/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_geotiff_plugins 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | * hector_geotiff/hector_geotiff_plugins: added possibility to specify Color of robot path in the geotiff file in order to allow multiple color robot paths 8 | * Contributors: Dorothea Koert 9 | 10 | 0.3.4 (2015-11-07) 11 | ------------------ 12 | 13 | 0.3.3 (2014-06-15) 14 | ------------------ 15 | 16 | 0.3.2 (2014-03-30) 17 | ------------------ 18 | 19 | 0.3.1 (2013-10-09) 20 | ------------------ 21 | * readded PLUGINLIB_DECLARE_CLASS macro for fuerte compatibility 22 | * use hector_geotiff_plugins/TrajectoryMapWriter as legacy lookup name for the trajectory geotiff plugin to not break old launch files 23 | * fixed warnings for deprecated pluginlib method/macro calls 24 | * added changelogs 25 | * added cmake dependencies to catkin exported targets to force message targets to be built before any cpp target using them 26 | 27 | 0.3.0 (2013-08-08) 28 | ------------------ 29 | * catkinized hector_slam 30 | -------------------------------------------------------------------------------- /hector_slam/hector_geotiff_plugins/hector_geotiff_plugins.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | This is a MapWriter plugin that draws the robot's trajectory in the map. 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /hector_slam/hector_imu_attitude_to_tf/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_imu_attitude_to_tf 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | 8 | 0.3.4 (2015-11-07) 9 | ------------------ 10 | * hector_imu_attitude_to_tf: fixed default values of the base_frame and base_stabilized_frame parameters (fix #20) 11 | * Contributors: Johannes Meyer 12 | 13 | 0.3.3 (2014-06-15) 14 | ------------------ 15 | 16 | 0.3.2 (2014-03-30) 17 | ------------------ 18 | 19 | 0.3.1 (2013-10-09) 20 | ------------------ 21 | * added missing install rule for launch files 22 | * added changelogs 23 | 24 | 0.3.0 (2013-08-08) 25 | ------------------ 26 | * catkinized hector_slam 27 | -------------------------------------------------------------------------------- /hector_slam/hector_imu_attitude_to_tf/launch/example.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /hector_slam/hector_imu_attitude_to_tf/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | hector_imu_attitude_to_tf 4 | 0.3.5 5 | 6 | hector_imu_attitude_to_tf is a lightweight node that can be used to publish the roll/pitch attitude angles reported via a imu message to tf. 7 | 8 | 9 | 10 | Johannes Meyer 11 | 12 | 13 | 14 | 15 | 16 | BSD 17 | 18 | 19 | 20 | 21 | 22 | http://ros.org/wiki/hector_imu_attitude_to_tf 23 | 24 | 25 | 26 | 27 | Stefan Kohlbrecher 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | catkin 42 | roscpp 43 | tf 44 | roscpp 45 | tf 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /hector_slam/hector_imu_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_imu_tools 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | 8 | 0.3.4 (2015-11-07) 9 | ------------------ 10 | * Fix sim setup 11 | * remap for bertl setup 12 | * Contributors: Florian Kunz, kohlbrecher 13 | 14 | 0.3.3 (2014-06-15) 15 | ------------------ 16 | * hector_imu_tools: Basics of simple height etimation 17 | * hector_imu_tools: Add tf publishers in hector_imu_tools 18 | * hector_imu_tools: Also write out fake odometry 19 | * hector_imu_tools: Fix typo 20 | * hector_imu_tools: Prevent race conditions in slam, formatting 21 | * hector_imu_tools: Small executable for generating a IMU message out of a (2d) pose and roll/pitch imu message 22 | * Contributors: Stefan Kohlbrecher 23 | -------------------------------------------------------------------------------- /hector_slam/hector_imu_tools/launch/bertl_robot.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /hector_slam/hector_imu_tools/launch/jasmine_robot.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /hector_slam/hector_map_server/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_map_server 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | 8 | 0.3.4 (2015-11-07) 9 | ------------------ 10 | 11 | 0.3.3 (2014-06-15) 12 | ------------------ 13 | 14 | 0.3.2 (2014-03-30) 15 | ------------------ 16 | 17 | 0.3.1 (2013-10-09) 18 | ------------------ 19 | * added changelogs 20 | * added cmake dependencies to catkin exported targets to force message targets to be built before any cpp target using them 21 | 22 | 0.3.0 (2013-08-08) 23 | ------------------ 24 | * catkinized hector_slam 25 | -------------------------------------------------------------------------------- /hector_slam/hector_map_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_map_tools 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | 8 | 0.3.4 (2015-11-07) 9 | ------------------ 10 | * -Fix severe bug when not using square size maps (would results in completely wrong obstacle distances and coordinates) 11 | * Contributors: Stefan Kohlbrecher 12 | 13 | 0.3.3 (2014-06-15) 14 | ------------------ 15 | 16 | 0.3.2 (2014-03-30) 17 | ------------------ 18 | 19 | 0.3.1 (2013-10-09) 20 | ------------------ 21 | * added changelogs 22 | 23 | 0.3.0 (2013-08-08) 24 | ------------------ 25 | * catkinized hector_slam 26 | -------------------------------------------------------------------------------- /hector_slam/hector_map_tools/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | hector_map_tools 4 | 0.3.5 5 | 6 | hector_map_tools contains some functions related to accessing information from OccupancyGridMap maps. 7 | Currently consists of a single header. 8 | 9 | 10 | 11 | Johannes Meyer 12 | 13 | 14 | 15 | 16 | 17 | BSD 18 | 19 | 20 | 21 | 22 | http://ros.org/wiki/hector_map_tools 23 | 24 | 25 | 26 | 27 | Stefan Kohlbrecher 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | catkin 42 | nav_msgs 43 | eigen 44 | nav_msgs 45 | eigen 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | -------------------------------------------------------------------------------- /hector_slam/hector_mapping/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_mapping 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | * Use the FindEigen3.cmake module provided by Eigen 8 | * Contributors: Johannes Meyer 9 | 10 | 0.3.4 (2015-11-07) 11 | ------------------ 12 | 13 | 0.3.3 (2014-06-15) 14 | ------------------ 15 | 16 | 0.3.2 (2014-03-30) 17 | ------------------ 18 | 19 | 0.3.1 (2013-10-09) 20 | ------------------ 21 | * respect ``p_map_frame_`` 22 | * added changelogs 23 | 24 | 0.3.0 (2013-08-08) 25 | ------------------ 26 | * catkinized hector_slam 27 | * hector_mapping: fixed multi-resolution map scan matching index bug in MapRepMultiMap.h 28 | -------------------------------------------------------------------------------- /hector_slam/hector_mapping/include/hector_slam_lib/map/GridMap.h: -------------------------------------------------------------------------------- 1 | //================================================================================================= 2 | // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt 3 | // All rights reserved. 4 | 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are met: 7 | // * Redistributions of source code must retain the above copyright 8 | // notice, this list of conditions and the following disclaimer. 9 | // * Redistributions in binary form must reproduce the above copyright 10 | // notice, this list of conditions and the following disclaimer in the 11 | // documentation and/or other materials provided with the distribution. 12 | // * Neither the name of the Simulation, Systems Optimization and Robotics 13 | // group, TU Darmstadt nor the names of its contributors may be used to 14 | // endorse or promote products derived from this software without 15 | // specific prior written permission. 16 | 17 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 18 | // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 19 | // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 20 | // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 21 | // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 22 | // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 23 | // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 24 | // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 26 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | //================================================================================================= 28 | 29 | #ifndef __GridMap_h_ 30 | #define __GridMap_h_ 31 | 32 | #include "OccGridMapBase.h" 33 | #include "GridMapLogOdds.h" 34 | #include "GridMapReflectanceCount.h" 35 | #include "GridMapSimpleCount.h" 36 | 37 | namespace hectorslam { 38 | 39 | typedef OccGridMapBase GridMap; 40 | //typedef OccGridMapBase GridMap; 41 | //typedef OccGridMapBase GridMap; 42 | 43 | } 44 | 45 | #endif 46 | -------------------------------------------------------------------------------- /hector_slam/hector_mapping/include/hector_slam_lib/util/HectorDebugInfoInterface.h: -------------------------------------------------------------------------------- 1 | //================================================================================================= 2 | // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt 3 | // All rights reserved. 4 | 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are met: 7 | // * Redistributions of source code must retain the above copyright 8 | // notice, this list of conditions and the following disclaimer. 9 | // * Redistributions in binary form must reproduce the above copyright 10 | // notice, this list of conditions and the following disclaimer in the 11 | // documentation and/or other materials provided with the distribution. 12 | // * Neither the name of the Simulation, Systems Optimization and Robotics 13 | // group, TU Darmstadt nor the names of its contributors may be used to 14 | // endorse or promote products derived from this software without 15 | // specific prior written permission. 16 | 17 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 18 | // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 19 | // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 20 | // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 21 | // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 22 | // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 23 | // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 24 | // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 26 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | //================================================================================================= 28 | 29 | #ifndef hectordebuginfointerface_h__ 30 | #define hectordebuginfointerface_h__ 31 | 32 | class HectorDebugInfoInterface{ 33 | public: 34 | 35 | virtual void sendAndResetData() = 0; 36 | virtual void addHessianMatrix(const Eigen::Matrix3f& hessian) = 0; 37 | virtual void addPoseLikelihood(float lh) = 0; 38 | }; 39 | 40 | #endif 41 | -------------------------------------------------------------------------------- /hector_slam/hector_mapping/include/hector_slam_lib/util/MapLockerInterface.h: -------------------------------------------------------------------------------- 1 | //================================================================================================= 2 | // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt 3 | // All rights reserved. 4 | 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are met: 7 | // * Redistributions of source code must retain the above copyright 8 | // notice, this list of conditions and the following disclaimer. 9 | // * Redistributions in binary form must reproduce the above copyright 10 | // notice, this list of conditions and the following disclaimer in the 11 | // documentation and/or other materials provided with the distribution. 12 | // * Neither the name of the Simulation, Systems Optimization and Robotics 13 | // group, TU Darmstadt nor the names of its contributors may be used to 14 | // endorse or promote products derived from this software without 15 | // specific prior written permission. 16 | 17 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 18 | // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 19 | // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 20 | // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 21 | // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 22 | // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 23 | // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 24 | // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 26 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | //================================================================================================= 28 | 29 | #ifndef maplockerinterface_h__ 30 | #define maplockerinterface_h__ 31 | 32 | class MapLockerInterface 33 | { 34 | public: 35 | virtual void lockMap() = 0; 36 | virtual void unlockMap() = 0; 37 | }; 38 | 39 | #endif 40 | -------------------------------------------------------------------------------- /hector_slam/hector_mapping/msg/HectorDebugInfo.msg: -------------------------------------------------------------------------------- 1 | HectorIterData[] iterData -------------------------------------------------------------------------------- /hector_slam/hector_mapping/msg/HectorIterData.msg: -------------------------------------------------------------------------------- 1 | float64[9] hessian 2 | float64 conditionNum 3 | float64 determinant 4 | float64 conditionNum2d 5 | float64 determinant2d 6 | -------------------------------------------------------------------------------- /hector_slam/hector_mapping/src/HectorMapMutex.h: -------------------------------------------------------------------------------- 1 | #ifndef hectormapmutex_h__ 2 | #define hectormapmutex_h__ 3 | 4 | #include "util/MapLockerInterface.h" 5 | 6 | #include 7 | 8 | class HectorMapMutex : public MapLockerInterface 9 | { 10 | public: 11 | virtual void lockMap() 12 | { 13 | mapModifyMutex_.lock(); 14 | } 15 | 16 | virtual void unlockMap() 17 | { 18 | mapModifyMutex_.unlock(); 19 | } 20 | 21 | boost::mutex mapModifyMutex_; 22 | }; 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /hector_slam/hector_mapping/src/main.cpp: -------------------------------------------------------------------------------- 1 | //================================================================================================= 2 | // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt 3 | // All rights reserved. 4 | 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are met: 7 | // * Redistributions of source code must retain the above copyright 8 | // notice, this list of conditions and the following disclaimer. 9 | // * Redistributions in binary form must reproduce the above copyright 10 | // notice, this list of conditions and the following disclaimer in the 11 | // documentation and/or other materials provided with the distribution. 12 | // * Neither the name of the Simulation, Systems Optimization and Robotics 13 | // group, TU Darmstadt nor the names of its contributors may be used to 14 | // endorse or promote products derived from this software without 15 | // specific prior written permission. 16 | 17 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 18 | // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 19 | // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 20 | // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 21 | // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 22 | // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 23 | // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 24 | // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 26 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | //================================================================================================= 28 | 29 | 30 | #include 31 | 32 | #include "HectorMappingRos.h" 33 | 34 | int main(int argc, char** argv) 35 | { 36 | ros::init(argc, argv, "hector_slam"); 37 | 38 | HectorMappingRos sm; 39 | 40 | ros::spin(); 41 | 42 | return(0); 43 | } 44 | 45 | -------------------------------------------------------------------------------- /hector_slam/hector_mapping/src/main_mapper.cpp: -------------------------------------------------------------------------------- 1 | //================================================================================================= 2 | // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt 3 | // All rights reserved. 4 | 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are met: 7 | // * Redistributions of source code must retain the above copyright 8 | // notice, this list of conditions and the following disclaimer. 9 | // * Redistributions in binary form must reproduce the above copyright 10 | // notice, this list of conditions and the following disclaimer in the 11 | // documentation and/or other materials provided with the distribution. 12 | // * Neither the name of the Simulation, Systems Optimization and Robotics 13 | // group, TU Darmstadt nor the names of its contributors may be used to 14 | // endorse or promote products derived from this software without 15 | // specific prior written permission. 16 | 17 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 18 | // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 19 | // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 20 | // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 21 | // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 22 | // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 23 | // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 24 | // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 26 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | //================================================================================================= 28 | 29 | 30 | #include 31 | 32 | #include "HectorMapperRos.h" 33 | 34 | int main(int argc, char** argv) 35 | { 36 | ros::init(argc, argv, "hector_slam"); 37 | 38 | HectorMapperRos sm; 39 | 40 | ros::spin(); 41 | 42 | return(0); 43 | } 44 | 45 | -------------------------------------------------------------------------------- /hector_slam/hector_marker_drawing/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_marker_drawing 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | * Use the FindEigen3.cmake module provided by Eigen 8 | * Contributors: Johannes Meyer 9 | 10 | 0.3.4 (2015-11-07) 11 | ------------------ 12 | 13 | 0.3.3 (2014-06-15) 14 | ------------------ 15 | * fixed cmake find for eigen in indigo 16 | * Contributors: Alexander Stumpf 17 | 18 | 0.3.2 (2014-03-30) 19 | ------------------ 20 | 21 | 0.3.1 (2013-10-09) 22 | ------------------ 23 | * added changelogs 24 | 25 | 0.3.0 (2013-08-08) 26 | ------------------ 27 | * catkinized hector_slam 28 | -------------------------------------------------------------------------------- /hector_slam/hector_marker_drawing/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | hector_marker_drawing 4 | 0.3.5 5 | 6 | hector_marker_drawing provides convenience functions for easier publishing of visualization markers. 7 | 8 | 9 | 10 | Johannes Meyer 11 | 12 | 13 | 14 | 15 | 16 | BSD 17 | 18 | 19 | 20 | 21 | http://ros.org/wiki/hector_marker_drawing 22 | 23 | 24 | 25 | 26 | Stefan Kohlbrecher 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | catkin 41 | roscpp 42 | visualization_msgs 43 | eigen 44 | roscpp 45 | visualization_msgs 46 | eigen 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /hector_slam/hector_nav_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_nav_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | 8 | 0.3.4 (2015-11-07) 9 | ------------------ 10 | * hector_nav_msgs: removed yaw member from GetNormal response 11 | yaw is implicitly given by the normal vector 12 | * Contributors: Dorothea Koert 13 | 14 | 0.3.3 (2014-06-15) 15 | ------------------ 16 | * added GetNormal service, that returns normal and orientation of an occupied cell 17 | * Contributors: Dorothea Koert 18 | 19 | 0.3.2 (2014-03-30) 20 | ------------------ 21 | 22 | 0.3.1 (2013-10-09) 23 | ------------------ 24 | * added changelogs 25 | 26 | 0.3.0 (2013-08-08) 27 | ------------------ 28 | * catkinized hector_slam 29 | -------------------------------------------------------------------------------- /hector_slam/hector_nav_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | hector_nav_msgs 4 | 0.3.5 5 | 6 | hector_nav_msgs contains messages and services used in the hector_slam stack. 7 | 8 | 9 | 10 | Johannes Meyer 11 | 12 | 13 | 14 | 15 | 16 | BSD 17 | 18 | 19 | 20 | 21 | http://ros.org/wiki/hector_nav_msgs 22 | 23 | 24 | 25 | 26 | Stefan Kohlbrecher 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | catkin 41 | nav_msgs 42 | geometry_msgs 43 | message_generation 44 | nav_msgs 45 | geometry_msgs 46 | message_runtime 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /hector_slam/hector_nav_msgs/srv/GetDistanceToObstacle.srv: -------------------------------------------------------------------------------- 1 | # Returns the distance to the next obstacle from the origin of frame point.header.frame_id 2 | # in the direction of the point 3 | # 4 | # All units are meters. 5 | 6 | geometry_msgs/PointStamped point 7 | --- 8 | float32 distance 9 | geometry_msgs/PointStamped end_point 10 | 11 | 12 | -------------------------------------------------------------------------------- /hector_slam/hector_nav_msgs/srv/GetNormal.srv: -------------------------------------------------------------------------------- 1 | geometry_msgs/PointStamped point 2 | --- 3 | geometry_msgs/Vector3 normal 4 | -------------------------------------------------------------------------------- /hector_slam/hector_nav_msgs/srv/GetRecoveryInfo.srv: -------------------------------------------------------------------------------- 1 | # Returns the path travelled to get to req_pose (pose determined by request_time) 2 | # up to request_radius away from req_pose. 3 | # 4 | 5 | time request_time 6 | float64 request_radius 7 | --- 8 | nav_msgs/Path trajectory_radius_entry_pose_to_req_pose 9 | geometry_msgs/PoseStamped radius_entry_pose 10 | geometry_msgs/PoseStamped req_pose 11 | 12 | -------------------------------------------------------------------------------- /hector_slam/hector_nav_msgs/srv/GetRobotTrajectory.srv: -------------------------------------------------------------------------------- 1 | # Returns the distance to the next obstacle from the origin of frame point.header.frame_id 2 | # in the direction of the point 3 | # 4 | # All units are meters. 5 | 6 | --- 7 | nav_msgs/Path trajectory 8 | 9 | -------------------------------------------------------------------------------- /hector_slam/hector_nav_msgs/srv/GetSearchPosition.srv: -------------------------------------------------------------------------------- 1 | #Returns a suggested search/observation position for an object of interest located at ooi_pose 2 | 3 | geometry_msgs/PoseStamped ooi_pose 4 | float32 distance 5 | --- 6 | geometry_msgs/PoseStamped search_pose 7 | 8 | -------------------------------------------------------------------------------- /hector_slam/hector_slam/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_slam 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | 8 | 0.3.4 (2015-11-07) 9 | ------------------ 10 | 11 | 0.3.3 (2014-06-15) 12 | ------------------ 13 | 14 | 0.3.2 (2014-03-30) 15 | ------------------ 16 | 17 | 0.3.1 (2013-10-09) 18 | ------------------ 19 | * added changelogs 20 | 21 | 0.3.0 (2013-08-08) 22 | ------------------ 23 | * catkinized hector_slam 24 | -------------------------------------------------------------------------------- /hector_slam/hector_slam/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(hector_slam) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_slam_launch 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | 8 | 0.3.4 (2015-11-07) 9 | ------------------ 10 | * Removes trailing spaces and fixes indents 11 | * "rviz_cfg" directory in the repository version. 12 | * Contributors: YuK_Ota, dani-carbonell 13 | 14 | 0.3.3 (2014-06-15) 15 | ------------------ 16 | 17 | 0.3.2 (2014-03-30) 18 | ------------------ 19 | * Add arguments to launch files for specifying geotiff file path 20 | * Update rviz config to have proper default displays 21 | * deleted quadrotor_uav.launch (moved to hector_quadrotor) 22 | * Contributors: Johannes Meyer, Stefan Kohlbrecher 23 | 24 | 0.3.1 (2013-10-09) 25 | ------------------ 26 | * updated rviz config to the new .rviz format 27 | * added changelogs 28 | 29 | 0.3.0 (2013-08-08) 30 | ------------------ 31 | * catkinized hector_slam 32 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/launch/hector_ugv.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/launch/height_mapping.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/launch/mapping_box.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 51 | 52 | 53 | 54 | 55 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/launch/mpo700_mapping.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/launch/postproc_data.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/launch/postproc_qut_logs.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/launch/tutorial.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /hector_slam/hector_slam_launch/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | hector_slam_launch 4 | 0.3.5 5 | 6 | hector_slam_launch contains launch files for launching hector_slam with different robot systems/setups/postprocessing scenarios. 7 | 8 | 9 | 10 | Johannes Meyer 11 | 12 | 13 | 14 | 15 | 16 | BSD 17 | 18 | 19 | 20 | 21 | http://ros.org/wiki/hector_slam_launch 22 | 23 | 24 | 25 | 26 | Stefan Kohlbrecher 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | catkin 41 | hector_mapping 42 | hector_map_server 43 | hector_trajectory_server 44 | hector_geotiff 45 | hector_geotiff_plugins 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | -------------------------------------------------------------------------------- /hector_slam/hector_trajectory_server/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_trajectory_server 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.5 (2016-06-24) 6 | ------------------ 7 | * Changed from ros::WallTime to ros::Time in trajectory server 8 | * hector_trajectory_server: removed bug leading to potential infinite loop 9 | * Contributors: Andreas Lindahl Flåten, Paul Manns 10 | 11 | 0.3.4 (2015-11-07) 12 | ------------------ 13 | 14 | 0.3.3 (2014-06-15) 15 | ------------------ 16 | 17 | 0.3.2 (2014-03-30) 18 | ------------------ 19 | * wait based on WallTime and check ros::ok() in waitForTf() 20 | * Print out tf availability warning only once. 21 | * Wait for tf become available to suppress warnings on startup 22 | * Create a warning instead of an error for TransformExceptions 23 | * Contributors: Johannes Meyer, Stefan Kohlbrecher, wachaja 24 | 25 | 0.3.1 (2013-10-09) 26 | ------------------ 27 | * added changelogs 28 | * added cmake dependencies to catkin exported targets to force message targets to be built before any cpp target using them 29 | 30 | 0.3.0 (2013-08-08) 31 | ------------------ 32 | * catkinized hector_slam 33 | -------------------------------------------------------------------------------- /hokuyo_node/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(hokuyo_node) 3 | 4 | find_package(Boost REQUIRED COMPONENTS system thread) 5 | 6 | # Utilities that use log4cxx - getID and getFirmwareVersion 7 | find_library(LOG4CXX_LIBRARY log4cxx) 8 | if(NOT LOG4CXX_LIBRARY) 9 | message(FATAL_ERROR "Couldn't find log4cxx library") 10 | endif() 11 | 12 | # Load catkin and all dependencies required for this package 13 | find_package(catkin REQUIRED 14 | COMPONENTS 15 | diagnostic_updater 16 | driver_base 17 | dynamic_reconfigure 18 | rosconsole 19 | roscpp 20 | self_test 21 | sensor_msgs 22 | ) 23 | 24 | include_directories(SYSTEM ${Boost_INCLUDE_DIRS}) 25 | include_directories(include ${catkin_INCLUDE_DIRS}) 26 | 27 | # Dynamic reconfigure support 28 | generate_dynamic_reconfigure_options(cfg/Hokuyo.cfg) 29 | 30 | # Export with catkin_package 31 | catkin_package( 32 | INCLUDE_DIRS include 33 | CATKIN_DEPENDS rosconsole 34 | LIBRARIES libhokuyo 35 | ) 36 | 37 | # Hokuyo library 38 | add_library(libhokuyo src/hokuyo.cpp) 39 | target_link_libraries(libhokuyo ${rosconsole_LIBRARIES}) 40 | 41 | # hokuyo_node 42 | add_executable(hokuyo_node src/hokuyo_node.cpp) 43 | add_dependencies(hokuyo_node ${PROJECT_NAME}_gencfg) 44 | target_link_libraries(hokuyo_node 45 | libhokuyo 46 | ${Boost_LIBRARIES} 47 | ${catkin_LIBRARIES} 48 | ) 49 | 50 | add_executable(getID src/getID.cpp) 51 | target_link_libraries(getID libhokuyo ${LOG4CXX_LIBRARY} ${catkin_LIBRARIES}) 52 | 53 | add_executable(getFirmwareVersion src/getFirmwareVersion.cpp) 54 | target_link_libraries(getFirmwareVersion 55 | libhokuyo 56 | ${LOG4CXX_LIBRARY} 57 | ${catkin_LIBRARIES} 58 | ) 59 | 60 | # Install targets 61 | install(TARGETS libhokuyo DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) 62 | 63 | install(DIRECTORY include/${PROJECT_NAME}/ 64 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 65 | ) 66 | 67 | install(TARGETS hokuyo_node getID getFirmwareVersion 68 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 69 | ) 70 | 71 | install(FILES test/TODO test/unplug_test.launch COPYING.lib hokuyo_test.launch hokuyo_test.vcg hokuyo_test_intensity.launch 72 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 73 | ) -------------------------------------------------------------------------------- /hokuyo_node/hokuyo_test.launch: -------------------------------------------------------------------------------- 1 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 31 | 32 | 33 | -------------------------------------------------------------------------------- /hokuyo_node/hokuyo_test.vcg: -------------------------------------------------------------------------------- 1 | Background\ ColorR=0 2 | Background\ ColorG=0 3 | Background\ ColorB=0 4 | Fixed\ Frame=/laser 5 | Target\ Frame=/laser 6 | Floor\ Scan.Alpha=1 7 | Floor\ Scan.Autocompute\ Intensity\ Bounds=1 8 | Floor\ Scan.Billboard\ Size=0.01 9 | Floor\ Scan.Channel=-1 10 | Floor\ Scan.Decay\ Time=0 11 | Floor\ Scan.Enabled=1 12 | Floor\ Scan.Max\ ColorR=0 13 | Floor\ Scan.Max\ ColorG=1 14 | Floor\ Scan.Max\ ColorB=0 15 | Floor\ Scan.Max\ Intensity=4096 16 | Floor\ Scan.Min\ ColorR=0 17 | Floor\ Scan.Min\ ColorG=0 18 | Floor\ Scan.Min\ ColorB=0 19 | Floor\ Scan.Min\ Intensity=0 20 | Floor\ Scan.Selectable=1 21 | Floor\ Scan.Style=1 22 | Floor\ Scan.Topic=/scan 23 | Grid.Alpha=0.5 24 | Grid.Cell\ Size=1 25 | Grid.ColorR=0.5 26 | Grid.ColorG=0.5 27 | Grid.ColorB=0.5 28 | Grid.Enabled=1 29 | Grid.Line\ Style=0 30 | Grid.Line\ Width=0.03 31 | Grid.Normal\ Cell\ Count=0 32 | Grid.OffsetX=0 33 | Grid.OffsetY=0 34 | Grid.OffsetZ=0 35 | Grid.Plane=0 36 | Grid.Plane\ Cell\ Count=10 37 | Grid.Reference\ Frame= 38 | Tool\ 2D\ Nav\ GoalTopic=goal 39 | Tool\ 2D\ Pose\ EstimateTopic=initialpose 40 | Camera\ Type=rviz::FixedOrientationOrthoViewController 41 | Camera\ Config=121.003 -0.957785 11.3941 -0.649553 -0.707107 -0 -0 0.707107 42 | Property\ Grid\ State=selection=;expanded=.Global Options;scrollpos=0,0;splitterpos=125,266;ispageselected=1 43 | [Display0] 44 | Name=Floor Scan 45 | Package=rviz 46 | ClassName=rviz::LaserScanDisplay 47 | [Display1] 48 | Name=Grid 49 | Package=rviz 50 | ClassName=rviz::GridDisplay 51 | -------------------------------------------------------------------------------- /hokuyo_node/hokuyo_test_intensity.launch: -------------------------------------------------------------------------------- 1 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /hokuyo_node/package.xml: -------------------------------------------------------------------------------- 1 | 2 | hokuyo_node 3 | 1.7.8 4 | A ROS node to provide access to SCIP 2.0-compliant Hokuyo laser range finders (including 04LX). 5 | Chad Rockey 6 | 7 | LGPL 8 | 9 | http://www.ros.org/wiki/hokuyo_node 10 | https://github.com/ros-drivers/hokuyo_node/issues 11 | https://github.com/ros-drivers/hokuyo_node 12 | 13 | Brian P. Gerkey 14 | Jeremy Leibs 15 | Blaise Gassend 16 | 17 | catkin 18 | 19 | rosconsole 20 | roscpp 21 | sensor_msgs 22 | driver_base 23 | self_test 24 | diagnostic_updater 25 | dynamic_reconfigure 26 | log4cxx 27 | 28 | rosconsole 29 | roscpp 30 | sensor_msgs 31 | driver_base 32 | self_test 33 | diagnostic_updater 34 | dynamic_reconfigure 35 | log4cxx 36 | 37 | 38 | -------------------------------------------------------------------------------- /hokuyo_node/src/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | find_library(LOG4CXX_LIBRARY log4cxx) 2 | if(NOT LOG4CXX_LIBRARY) 3 | message(FATAL_ERROR "Couldn't find log4cxx library") 4 | endif() 5 | 6 | rosbuild_add_executable(getID getID.cpp) 7 | target_link_libraries(getID libhokuyo ${LOG4CXX_LIBRARY}) 8 | 9 | rosbuild_add_executable(getFirmwareVersion getFirmwareVersion.cpp) 10 | target_link_libraries(getFirmwareVersion libhokuyo ${LOG4CXX_LIBRARY}) 11 | -------------------------------------------------------------------------------- /hokuyo_node/test/TODO: -------------------------------------------------------------------------------- 1 | Need to check: 2 | * Unplug/replug doesn't kill the driver. 3 | * Starting up with the laser scanning doesn't cause problems. 4 | -------------------------------------------------------------------------------- /hokuyo_node/test/unplug_test.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /octomap_mapping/.gitignore: -------------------------------------------------------------------------------- 1 | # Compiled Object files 2 | *.slo 3 | *.lo 4 | *.o 5 | 6 | # Compiled Dynamic libraries 7 | *.so 8 | *.dylib 9 | 10 | # Compiled Static libraries 11 | *.lai 12 | *.la 13 | *.a 14 | 15 | octomap_server/docs 16 | octomap_server/cfg 17 | octomap_server/src/octomap_server 18 | -------------------------------------------------------------------------------- /octomap_mapping/.travis.yml: -------------------------------------------------------------------------------- 1 | # This config file for Travis CI utilizes ros-industrial/industrial_ci package. 2 | # For more info for the package, see https://github.com/ros-industrial/industrial_ci/blob/master/README.rst 3 | sudo: required 4 | language: generic 5 | env: 6 | global: 7 | - ROS_PARALLEL_JOBS=-j4 # Don't exhaust virtual memory 8 | matrix: 9 | - ROS_DISTRO="kinetic" CATKIN_CONFIG='-DCMAKE_BUILD_TYPE=Debug' 10 | - ROS_DISTRO="kinetic" CATKIN_CONFIG='-DCMAKE_BUILD_TYPE=Release' 11 | - ROS_DISTRO="kinetic" PRERELEASE=true 12 | - ROS_DISTRO="melodic" CATKIN_CONFIG='-DCMAKE_BUILD_TYPE=Debug' 13 | - ROS_DISTRO="melodic" CATKIN_CONFIG='-DCMAKE_BUILD_TYPE=Release' 14 | - ROS_DISTRO="melodic" PRERELEASE=true 15 | - ROS_DISTRO="melodic" OS_NAME="debian" OS_CODE_NAME="stretch" 16 | matrix: 17 | allow_failures: 18 | - env: ROS_DISTRO="kinetic" PRERELEASE=true 19 | - env: ROS_DISTRO="melodic" PRERELEASE=true 20 | install: 21 | - git clone --quiet --depth 1 https://github.com/ros-industrial/industrial_ci.git .ci_config 22 | script: 23 | - source .ci_config/travis.sh 24 | -------------------------------------------------------------------------------- /octomap_mapping/README.md: -------------------------------------------------------------------------------- 1 | octomap_mapping 2 | =============== 3 | 4 | ROS stack for mapping with OctoMap, contains the octomap_server package. 5 | 6 | The `master` branch tracks the latest (stable) releases. Please send pull requests against the latest development branch, e.g. `indigo-devel`. 7 | 8 | Indigo: [![Build Status](https://travis-ci.org/OctoMap/octomap_mapping.svg?branch=indigo-devel)](https://travis-ci.org/OctoMap/octomap_mapping) 9 | 10 | Kinetic/Melodic: [![Build Status](https://travis-ci.org/OctoMap/octomap_mapping.svg?branch=kinetic-devel)](https://travis-ci.org/OctoMap/octomap_mapping) 11 | 12 | 13 | 14 | Imported from SVN, see https://code.google.com/p/alufr-ros-pkg/ for the previous versions. 15 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_mapping/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package octomap_mapping 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.6.3 (2019-01-28) 6 | ------------------ 7 | 8 | 0.6.2 (2019-01-27) 9 | ------------------ 10 | * Update maintainer email (Wolfgang Merkt) 11 | * Contributors: Wolfgang Merkt 12 | 13 | 0.6.1 (2016-10-19) 14 | ------------------ 15 | * Adjust maintainer email 16 | * Contributors: Armin Hornung 17 | 18 | 0.6.0 (2016-03-25) 19 | ------------------ 20 | 21 | 0.5.3 (2014-01-09) 22 | ------------------ 23 | 24 | 0.5.2 (2014-01-09) 25 | ------------------ 26 | 27 | 0.5.1 (2013-11-25) 28 | ------------------ 29 | 30 | 0.5.0 (2013-10-24) 31 | ------------------ 32 | * URLs in package.xml 33 | * Catkinization, remove support for arm_navigation 34 | 35 | 0.4.9 (2013-06-27) 36 | ------------------ 37 | 38 | 0.4.8 (2013-01-08) 39 | ------------------ 40 | 41 | 0.4.6 (2013-01-28) 42 | ------------------ 43 | 44 | 0.4.5 (2012-06-18) 45 | ------------------ 46 | 47 | 0.4.4 (2012-04-20) 48 | ------------------ 49 | 50 | 0.4.3 (2012-04-17) 51 | ------------------ 52 | 53 | 0.4.2 (2012-03-16) 54 | ------------------ 55 | 56 | 0.4.1 (2012-02-21 16:50) 57 | ------------------------ 58 | 59 | 0.4.0 (2012-02-21 15:37) 60 | ------------------------ 61 | 62 | 0.3.8 (2012-04-26) 63 | ------------------ 64 | 65 | 0.3.7 (2012-02-22) 66 | ------------------ 67 | 68 | 0.3.6 (2012-01-09) 69 | ------------------ 70 | 71 | 0.3.5 (2011-10-30) 72 | ------------------ 73 | 74 | 0.3.4 (2011-10-12) 75 | ------------------ 76 | 77 | 0.3.3 (2011-08-17 07:41) 78 | ------------------------ 79 | 80 | 0.3.2 (2011-08-09) 81 | ------------------ 82 | 83 | 0.3.1 (2011-07-15) 84 | ------------------ 85 | 86 | 0.3.0 (2011-06-28) 87 | ------------------ 88 | 89 | 0.2.0 (2011-03-16) 90 | ------------------ 91 | 92 | 0.1.2 (2010-11-23) 93 | ------------------ 94 | 95 | 0.1.1 (2010-11-17) 96 | ------------------ 97 | 98 | 0.1.0 (2010-11-16) 99 | ------------------ 100 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_mapping/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(octomap_mapping) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_mapping/package.xml: -------------------------------------------------------------------------------- 1 | 2 | octomap_mapping 3 | 0.6.3 4 | 5 | Mapping tools to be used with the OctoMap library, implementing a 3D occupancy grid mapping. 6 | 7 | Armin Hornung 8 | Wolfgang Merkt 9 | BSD 10 | 11 | http://ros.org/wiki/octomap_mapping 12 | https://github.com/OctoMap/octomap_mapping/issues 13 | https://github.com/OctoMap/octomap_mapping 14 | 15 | catkin 16 | octomap_server 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/launch/octomap_mapping.launch: -------------------------------------------------------------------------------- 1 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/launch/octomap_mapping_nodelet.launch: -------------------------------------------------------------------------------- 1 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/launch/octomap_tracking_client.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/launch/octomap_tracking_server.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b octomap_server is ... 6 | 7 | 14 | 15 | 16 | \section codeapi Code API 17 | 18 | 28 | 29 | 30 | */ -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/nodelet_plugins.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Nodelet for running the Octomap server 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/package.xml: -------------------------------------------------------------------------------- 1 | 2 | octomap_server 3 | 0.6.3 4 | 5 | octomap_server loads a 3D map (as Octree-based OctoMap) and distributes it to other nodes in a compact binary format. It also allows to incrementally build 3D OctoMaps, and provides map saving in the node octomap_saver. 6 | 7 | Armin Hornung 8 | Wolfgang Merkt 9 | BSD 10 | http://www.ros.org/wiki/octomap_server 11 | https://github.com/OctoMap/octomap_mapping/issues 12 | https://github.com/OctoMap/octomap_mapping 13 | 14 | 15 | 16 | 17 | 18 | catkin 19 | 20 | roscpp 21 | visualization_msgs 22 | sensor_msgs 23 | pcl_ros 24 | pcl_conversions 25 | nav_msgs 26 | std_msgs 27 | std_srvs 28 | octomap 29 | octomap_msgs 30 | octomap_ros 31 | dynamic_reconfigure 32 | nodelet 33 | libpcl-all-dev 34 | 35 | roscpp 36 | visualization_msgs 37 | sensor_msgs 38 | pcl_ros 39 | pcl_conversions 40 | nav_msgs 41 | std_msgs 42 | std_srvs 43 | octomap 44 | octomap_msgs 45 | octomap_ros 46 | dynamic_reconfigure 47 | nodelet 48 | libpcl-all 49 | 50 | 51 | 52 | 53 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/params/default.yaml: -------------------------------------------------------------------------------- 1 | # Empty file to load default parameters. 2 | -------------------------------------------------------------------------------- /octomap_mapping/octomap_server/scripts/octomap_eraser_cli.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | """Clear a region specified by a global axis-aligned bounding box in stored 4 | OctoMap. 5 | 6 | """ 7 | 8 | import sys 9 | from time import sleep 10 | 11 | import roslib 12 | roslib.load_manifest('octomap_server') 13 | from geometry_msgs.msg import Point 14 | import octomap_msgs.srv 15 | import rospy 16 | 17 | 18 | SRV_NAME = '/octomap_server/clear_bbx' 19 | SRV_INTERFACE = octomap_msgs.srv.BoundingBoxQuery 20 | 21 | 22 | if __name__ == '__main__': 23 | min = Point(*[float(x) for x in sys.argv[1:4]]) 24 | max = Point(*[float(x) for x in sys.argv[4:7]]) 25 | 26 | rospy.init_node('octomap_eraser_cli', anonymous=True) 27 | sleep(1) 28 | service = rospy.ServiceProxy(SRV_NAME, SRV_INTERFACE) 29 | rospy.loginfo("Connected to %s service." % SRV_NAME) 30 | 31 | service(min, max) 32 | -------------------------------------------------------------------------------- /scoutrobot_control/Launch Commands.txt: -------------------------------------------------------------------------------- 1 | cd catkin_ws 2 | source devel/setup.bash 3 | roslaunch cvg_sim_gazebo scoutrobot_world_2.launch 4 | roslaunch hector_mapping mapping_default.launch 5 | rosrun scoutrobot_control scoutrobot_control.py 6 | rqt_graph 7 | roslaunch openni_launch openni.launch 8 | 9 | 10 | BEBOP: 11 | roslaunch bebop_driver bebop_node.launch 12 | rostopic pub --once [namespace]/takeoff std_msgs/Empty 13 | rostopic pub --once [namespace]/land std_msgs/Empty 14 | 15 | KEYBOARD: 16 | rosrun teleop_twist_keyboard teleop_twist_keyboard_custom.py 17 | 18 | MOVEIT 19 | roslaunch scoutrobot_moveit_config demo.launch 20 | 21 | OCTOMAP 22 | roslaunch octomap_server octomap_mapping.launch 23 | 24 | MANUAL 25 | Takeoff: 26 | rostopic pub -1 /ardrone/takeoff std_msgs/Empty 27 | rostopic pub -r 10 /cmd_vel geometry_msgs/Twist '{linear: {x: 0.1, y: 0.0, z: 0.0}, angular: {x: 0.0,y: 0.0,z: 0.0}}' -------------------------------------------------------------------------------- /teleop_twist_keyboard/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | 0.6.2 (2018-10-21) 2 | ------------------ 3 | * Replace tabs with spaces, fixes `#15 `_ 4 | * Merge pull request `#13 `_ from asukiaaa/patch-3 5 | Add rosrun command to specify values 6 | * Add rosrun command to specify values 7 | * Contributors: Asuki Kono, Austin, trainman419 8 | 9 | 0.6.1 (2018-05-02) 10 | ------------------ 11 | * Merge pull request `#11 `_ from MatthijsBurgh/patch-1 12 | Correct exception handling; Python3 print compatible 13 | * import print from future 14 | * Print python3 compatible 15 | * correct Exception handling 16 | * Merge pull request `#7 `_ from lucasw/speed_params 17 | set linear and turn speed via rosparams 18 | * Using tabs instead of spaces to match rest of file 19 | * set linear and turn speed via rosparams 20 | * Contributors: Austin, Lucas Walter, Matthijs van der Burgh 21 | 22 | 0.6.0 (2016-03-21) 23 | ------------------ 24 | * Better instruction formatting 25 | * support holonomic base, send commmand with keyboard down 26 | * Fixing queue_size warning 27 | * Create README.md 28 | * Update the description string in package.xml 29 | * Contributors: Austin, Kei Okada, LiohAu, Mike Purvis, kk6axq, trainman419 30 | 31 | 0.5.0 (2014-02-11) 32 | ------------------ 33 | * Initial import from brown_remotelab 34 | * Convert to catkin 35 | -------------------------------------------------------------------------------- /teleop_twist_keyboard/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(teleop_twist_keyboard) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | ## Mark executable scripts (Python etc.) for installation 9 | ## in contrast to setup.py, you can choose the destination 10 | catkin_install_python(PROGRAMS 11 | teleop_twist_keyboard.py 12 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 13 | ) 14 | 15 | -------------------------------------------------------------------------------- /teleop_twist_keyboard/README.md: -------------------------------------------------------------------------------- 1 | # teleop_twist_keyboard 2 | Generic Keyboard Teleop for ROS 3 | 4 | # Launch 5 | Run. 6 | ``` 7 | rosrun teleop_twist_keyboard teleop_twist_keyboard.py 8 | ``` 9 | 10 | With custom values. 11 | ``` 12 | rosrun teleop_twist_keyboard teleop_twist_keyboard.py _speed:=0.9 _turn:=0.8 13 | ``` 14 | 15 | Publishing to a different topic (in this case `my_cmd_vel`). 16 | ``` 17 | rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=my_cmd_vel 18 | ``` 19 | 20 | # Usage 21 | ``` 22 | Reading from the keyboard and Publishing to Twist! 23 | --------------------------- 24 | Moving around: 25 | u i o 26 | j k l 27 | m , . 28 | 29 | For Holonomic mode (strafing), hold down the shift key: 30 | --------------------------- 31 | U I O 32 | J K L 33 | M < > 34 | 35 | t : up (+z) 36 | b : down (-z) 37 | 38 | anything else : stop 39 | 40 | q/z : increase/decrease max speeds by 10% 41 | w/x : increase/decrease only linear speed by 10% 42 | e/c : increase/decrease only angular speed by 10% 43 | 44 | CTRL-C to quit 45 | ``` 46 | 47 | -------------------------------------------------------------------------------- /teleop_twist_keyboard/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | teleop_twist_keyboard 4 | 0.6.2 5 | Generic keyboard teleop for twist robots. 6 | 7 | Austin Hendrix 8 | 9 | BSD 10 | 11 | http://wiki.ros.org/teleop_twist_keyboard 12 | 13 | Graylin Trevor Jay 14 | 15 | catkin 16 | geometry_msgs 17 | rospy 18 | 19 | --------------------------------------------------------------------------------