├── .gitignore ├── 3rdparty ├── fly_sim │ ├── mav_comm │ │ ├── .clang-format │ │ ├── README.md │ │ └── mav_msgs │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── cmake │ │ │ └── export_flags.cmake │ │ │ ├── include │ │ │ └── mav_msgs │ │ │ │ ├── common.h │ │ │ │ ├── conversions.h │ │ │ │ ├── default_topics.h │ │ │ │ ├── default_values.h │ │ │ │ └── eigen_mav_msgs.h │ │ │ ├── msg │ │ │ ├── Actuators.msg │ │ │ ├── AttitudeThrust.msg │ │ │ ├── FilteredSensorData.msg │ │ │ ├── GpsWaypoint.msg │ │ │ ├── RateThrust.msg │ │ │ ├── RollPitchYawrateThrust.msg │ │ │ ├── Status.msg │ │ │ └── TorqueThrust.msg │ │ │ └── package.xml │ └── rotors_fly │ │ ├── README.md │ │ ├── dependencies.rosinstall │ │ ├── rotors_comm │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── msg │ │ │ └── WindSpeed.msg │ │ ├── package.xml │ │ └── srv │ │ │ ├── Octomap.srv │ │ │ └── RecordRosbag.srv │ │ ├── rotors_control │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── include │ │ │ └── rotors_control │ │ │ │ ├── attitude_controller.h │ │ │ │ ├── attitude_controller_samy.h │ │ │ │ ├── common.h │ │ │ │ ├── lee_position_controller.h │ │ │ │ ├── motor_controller.h │ │ │ │ ├── parameters.h │ │ │ │ ├── parameters_ros.h │ │ │ │ ├── rate_controller.h │ │ │ │ └── roll_pitch_yawrate_thrust_controller.h │ │ ├── package.xml │ │ └── src │ │ │ ├── attitude_controller.cpp │ │ │ ├── attitude_controller_samy.cpp │ │ │ ├── library │ │ │ ├── lee_position_controller.cpp │ │ │ └── roll_pitch_yawrate_thrust_controller.cpp │ │ │ ├── motor_controller.cpp │ │ │ ├── nodes │ │ │ ├── lee_position_controller_node.cpp │ │ │ ├── lee_position_controller_node.h │ │ │ ├── roll_pitch_yawrate_thrust_controller_node.cpp │ │ │ └── roll_pitch_yawrate_thrust_controller_node.h │ │ │ └── rate_controller.cpp │ │ ├── rotors_demos.rosinstall │ │ ├── rotors_gazebo_plugins │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── autobackport │ │ │ ├── command.sh │ │ │ ├── commandpre7.sh │ │ │ ├── seds.txt │ │ │ └── seds_pre7.txt │ │ ├── cmake │ │ │ ├── FindEigen.cmake │ │ │ ├── FindGlog.cmake │ │ │ └── Findmavlink.cmake │ │ ├── include │ │ │ ├── liftdrag_plugin │ │ │ │ └── liftdrag_plugin.h │ │ │ └── rotors_gazebo_plugins │ │ │ │ ├── common.h │ │ │ │ ├── depth_noise_model.hpp │ │ │ │ ├── external │ │ │ │ ├── gazebo_geotagged_images_plugin.h │ │ │ │ ├── gazebo_gimbal_controller_plugin.h │ │ │ │ ├── gazebo_gst_camera_plugin.h │ │ │ │ ├── gazebo_lidar_plugin.h │ │ │ │ └── gazebo_optical_flow_plugin.h │ │ │ │ ├── fw_parameters.h │ │ │ │ ├── gazebo_bag_plugin.h │ │ │ │ ├── gazebo_controller_interface.h │ │ │ │ ├── gazebo_fw_dynamics_plugin.h │ │ │ │ ├── gazebo_gps_plugin.h │ │ │ │ ├── gazebo_imu_plugin.h │ │ │ │ ├── gazebo_magnetometer_plugin.h │ │ │ │ ├── gazebo_mavlink_interface.h │ │ │ │ ├── gazebo_motor_model.h │ │ │ │ ├── gazebo_multirotor_base_plugin.h │ │ │ │ ├── gazebo_noisydepth_plugin.h │ │ │ │ ├── gazebo_octomap_plugin.h │ │ │ │ ├── gazebo_odometry_plugin.h │ │ │ │ ├── gazebo_pressure_plugin.h │ │ │ │ ├── gazebo_ros_interface_plugin.h │ │ │ │ ├── gazebo_wind_plugin.h │ │ │ │ ├── geo_mag_declination.h │ │ │ │ ├── motor_controller.hpp │ │ │ │ ├── motor_model.hpp │ │ │ │ ├── msgbuffer.h │ │ │ │ ├── multi_copter.hpp │ │ │ │ └── sdf_api_wrapper.hpp │ │ ├── msgs │ │ │ ├── Actuators.proto │ │ │ ├── CommandMotorSpeed.proto │ │ │ ├── ConnectGazeboToRosTopic.proto │ │ │ ├── ConnectRosToGazeboTopic.proto │ │ │ ├── Float32.proto │ │ │ ├── FluidPressure.proto │ │ │ ├── Header.proto │ │ │ ├── Imu.proto │ │ │ ├── JointState.proto │ │ │ ├── Lidar.proto │ │ │ ├── MagneticField.proto │ │ │ ├── NavSatFix.proto │ │ │ ├── Odometry.proto │ │ │ ├── OpticalFlow.proto │ │ │ ├── Point.proto │ │ │ ├── PointStamped.proto │ │ │ ├── PoseStamped.proto │ │ │ ├── PoseWithCovariance.proto │ │ │ ├── PoseWithCovarianceStamped.proto │ │ │ ├── RollPitchYawrateThrust.proto │ │ │ ├── Transform.proto │ │ │ ├── TransformStamped.proto │ │ │ ├── TransformStampedWithFrameIds.proto │ │ │ ├── Twist.proto │ │ │ ├── TwistStamped.proto │ │ │ ├── TwistWithCovariance.proto │ │ │ ├── Vector3dStamped.proto │ │ │ ├── WindSpeed.proto │ │ │ ├── Wrench.proto │ │ │ └── WrenchStamped.proto │ │ ├── package.xml │ │ └── src │ │ │ ├── depth_noise_model.cpp │ │ │ ├── external │ │ │ ├── gazebo_geotagged_images_plugin.cpp │ │ │ ├── gazebo_gimbal_controller_plugin.cpp │ │ │ ├── gazebo_gst_camera_plugin.cpp │ │ │ ├── gazebo_lidar_plugin.cpp │ │ │ └── gazebo_optical_flow_plugin.cpp │ │ │ ├── gazebo_bag_plugin.cpp │ │ │ ├── gazebo_controller_interface.cpp │ │ │ ├── gazebo_fw_dynamics_plugin.cpp │ │ │ ├── gazebo_gps_plugin.cpp │ │ │ ├── gazebo_imu_plugin.cpp │ │ │ ├── gazebo_magnetometer_plugin.cpp │ │ │ ├── gazebo_mavlink_interface.cpp │ │ │ ├── gazebo_motor_model.cpp │ │ │ ├── gazebo_multirotor_base_plugin.cpp │ │ │ ├── gazebo_noisydepth_plugin.cpp │ │ │ ├── gazebo_octomap_plugin.cpp │ │ │ ├── gazebo_odometry_no_tf_plugin.cpp │ │ │ ├── gazebo_odometry_plugin.cpp │ │ │ ├── gazebo_pressure_plugin.cpp │ │ │ ├── gazebo_ros_interface_plugin.cpp │ │ │ ├── gazebo_wind_plugin.cpp │ │ │ ├── geo_mag_declination.cpp │ │ │ └── liftdrag_plugin │ │ │ └── liftdrag_plugin.cpp │ │ ├── rotors_hil.rosinstall │ │ └── rotors_minimal.rosinstall ├── jackal │ ├── jackal_control │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── config │ │ │ ├── control.yaml │ │ │ ├── robot_localization.yaml │ │ │ ├── teleop.yaml │ │ │ ├── teleop_ps4.yaml │ │ │ └── twist_mux.yaml │ │ ├── launch │ │ │ ├── control.launch │ │ │ └── teleop.launch │ │ └── package.xml │ ├── jackal_description │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── launch │ │ │ └── description.launch │ │ ├── meshes │ │ │ ├── accessory_fender.stl │ │ │ ├── ark_enclosure.stl │ │ │ ├── bridge-plate.stl │ │ │ ├── camera-beam.stl │ │ │ ├── camera-bracket.stl │ │ │ ├── hokuyo_ust10.stl │ │ │ ├── jackal-base.stl │ │ │ ├── jackal-fender.stl │ │ │ ├── jackal-fenders.stl │ │ │ ├── jackal-wheel.stl │ │ │ ├── novatel-smart6.stl │ │ │ ├── sick-lms1xx-bracket.stl │ │ │ ├── stereo-camera-beam.stl │ │ │ └── stereo-camera-bracket.stl │ │ ├── package.xml │ │ ├── scripts │ │ │ ├── env_run │ │ │ └── env_run.bat │ │ └── urdf │ │ │ ├── VLP_16.urdf.xacro │ │ │ ├── accessories.urdf.xacro │ │ │ ├── accessories │ │ │ ├── bridge_plate.urdf.xacro │ │ │ ├── camera_mount.urdf.xacro │ │ │ ├── hokuyo_ust10.urdf.xacro │ │ │ ├── novatel_smart6.urdf.xacro │ │ │ ├── sick_lms1xx_mount.urdf.xacro │ │ │ ├── standoffs.urdf.xacro │ │ │ ├── stereo_camera_mount.urdf.xacro │ │ │ └── vlp16_mount.urdf.xacro │ │ │ ├── configs │ │ │ ├── base │ │ │ ├── base.bat │ │ │ ├── front_bumblebee2 │ │ │ ├── front_bumblebee2.bat │ │ │ ├── front_flea3 │ │ │ ├── front_flea3.bat │ │ │ ├── front_laser │ │ │ └── front_laser.bat │ │ │ ├── custom_example.urdf │ │ │ ├── empty.urdf │ │ │ ├── jackal.gazebo │ │ │ └── jackal.urdf.xacro │ ├── jackal_gazebo │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── Media │ │ │ └── models │ │ │ │ ├── OliveTree1.dae │ │ │ │ ├── OliveTree2.dae │ │ │ │ ├── PineTree.dae │ │ │ │ ├── scenario1.dae │ │ │ │ └── textures │ │ │ │ ├── Vegetation_Grass1.jpg │ │ │ │ ├── mtt.png │ │ │ │ ├── texture0.jpg │ │ │ │ └── texture0.png │ │ ├── launch │ │ │ ├── jackal_model.launch │ │ │ └── jackal_world.launch │ │ ├── package.xml │ │ └── worlds │ │ │ ├── empty.world │ │ │ ├── jackal_race.world │ │ │ └── scenario1.world │ ├── jackal_msgs │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── msg │ │ │ ├── Drive.msg │ │ │ ├── DriveFeedback.msg │ │ │ ├── Feedback.msg │ │ │ └── Status.msg │ │ └── package.xml │ └── jackal_simulator │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ └── package.xml ├── nmea_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── LICENSE.txt │ ├── README.rst │ ├── msg │ │ ├── Gpgga.msg │ │ ├── Gpgsa.msg │ │ ├── Gpgst.msg │ │ ├── Gpgsv.msg │ │ ├── GpgsvSatellite.msg │ │ ├── Gprmc.msg │ │ └── Sentence.msg │ └── package.xml ├── rosserial │ ├── .travis.yml │ ├── README.md │ ├── rosserial_msgs │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── msg │ │ │ ├── Log.msg │ │ │ └── TopicInfo.msg │ │ ├── package.xml │ │ └── srv │ │ │ └── RequestParam.srv │ └── rosserial_server │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── include │ │ └── rosserial_server │ │ │ ├── async_read_buffer.h │ │ │ ├── msg_lookup.h │ │ │ ├── serial_session.h │ │ │ ├── session.h │ │ │ ├── tcp_server.h │ │ │ ├── topic_handlers.h │ │ │ ├── udp_socket_session.h │ │ │ └── udp_stream.h │ │ ├── launch │ │ ├── serial.launch │ │ ├── socket.launch │ │ └── udp_socket.launch │ │ ├── package.xml │ │ └── src │ │ ├── msg_lookup.cpp │ │ ├── serial_node.cpp │ │ ├── socket_node.cpp │ │ └── udp_socket_node.cpp └── ufomap │ ├── LICENSE │ ├── README.md │ ├── ufomap │ ├── .clang-format │ ├── CMakeLists.txt │ ├── Doxyfile │ ├── README.md │ ├── cmake │ │ └── ufomapConfig.cmake.in │ ├── docs │ │ └── CMakeLists.txt │ ├── include │ │ └── ufo │ │ │ ├── geometry │ │ │ ├── README.md │ │ │ ├── aabb.h │ │ │ ├── bounding_volume.h │ │ │ ├── capsule.h │ │ │ ├── collision_checks.h │ │ │ ├── cone.h │ │ │ ├── cylinder.h │ │ │ ├── ellipsoid.h │ │ │ ├── frustum.h │ │ │ ├── line_segment.h │ │ │ ├── obb.h │ │ │ ├── plane.h │ │ │ ├── point.h │ │ │ ├── ray.h │ │ │ ├── sphere.h │ │ │ ├── triangle.h │ │ │ └── types.h │ │ │ ├── map │ │ │ ├── code.h │ │ │ ├── color.h │ │ │ ├── iterator │ │ │ │ ├── occupancy_map.h │ │ │ │ ├── occupancy_map_nearest.h │ │ │ │ ├── octree.h │ │ │ │ └── octree_nearest.h │ │ │ ├── key.h │ │ │ ├── occupancy_map.h │ │ │ ├── occupancy_map_base.h │ │ │ ├── occupancy_map_color.h │ │ │ ├── occupancy_map_node.h │ │ │ ├── octree.h │ │ │ ├── octree_node.h │ │ │ ├── point_cloud.h │ │ │ ├── types.h │ │ │ └── ufomap.h │ │ │ └── math │ │ │ ├── pose6.h │ │ │ ├── quaternion.h │ │ │ └── vector3.h │ ├── package.xml │ ├── src │ │ ├── geometry │ │ │ ├── bounding_volume.cpp │ │ │ └── collision_checks.cpp │ │ └── map │ │ │ ├── occupancy_map.cpp │ │ │ └── occupancy_map_color.cpp │ └── tests │ │ └── CMakeLists.txt │ └── ufomap_ros │ ├── .clang-format │ ├── README.md │ ├── ufomap_manager │ ├── CMakeLists.txt │ ├── include │ │ └── ufomap_manager │ │ │ ├── frontier_manager.h │ │ │ └── ufomap_manager.h │ ├── msg │ │ ├── CellCode.msg │ │ └── UfomapWithFrontiers.msg │ ├── package.xml │ └── src │ │ ├── frontier_manager.cpp │ │ ├── frontier_manager_node.cpp │ │ ├── read_trajectory.cpp │ │ ├── read_ufomap_node.cpp │ │ ├── statics.py │ │ ├── ufomap_manager.cpp │ │ └── ufomap_manager_node.cpp │ ├── ufomap_mapping │ ├── .clang-format │ ├── CMakeLists.txt │ ├── README.md │ ├── cfg │ │ └── Server.cfg │ ├── include │ │ └── ufomap_mapping │ │ │ └── server.h │ ├── launch │ │ └── server.launch │ ├── package.xml │ └── src │ │ ├── server.cpp │ │ └── server_node.cpp │ ├── ufomap_msgs │ ├── CMakeLists.txt │ ├── include │ │ └── ufomap_msgs │ │ │ └── conversions.h │ ├── msg │ │ ├── AABB.msg │ │ ├── BoundingVolume.msg │ │ ├── Capsule.msg │ │ ├── Cone.msg │ │ ├── Cylinder.msg │ │ ├── Ellipsoid.msg │ │ ├── Frustum.msg │ │ ├── LineSegment.msg │ │ ├── OBB.msg │ │ ├── Plane.msg │ │ ├── Point.msg │ │ ├── Ray.msg │ │ ├── Sphere.msg │ │ ├── Triangle.msg │ │ ├── UFOMap.msg │ │ ├── UFOMapMetaData.msg │ │ └── UFOMapStamped.msg │ ├── package.xml │ └── src │ │ └── conversions.cpp │ ├── ufomap_ros │ ├── CMakeLists.txt │ ├── include │ │ └── ufomap_ros │ │ │ └── conversions.h │ ├── package.xml │ └── src │ │ └── conversions.cpp │ ├── ufomap_rviz_plugins │ ├── CMakeLists.txt │ ├── include │ │ └── ufomap_rviz_plugins │ │ │ └── ufomap_display.h │ ├── package.xml │ ├── plugin_description.xml │ └── src │ │ └── ufomap_display.cpp │ └── ufomap_srvs │ ├── CMakeLists.txt │ ├── package.xml │ └── srv │ ├── ClearVolume.srv │ ├── GetMap.srv │ ├── Reset.srv │ └── SaveMap.srv ├── README.md ├── fael_planner ├── control_planner_interface │ ├── CMakeLists.txt │ ├── action │ │ ├── ExplorerPlanner.action │ │ └── VehicleExecute.action │ ├── include │ │ └── control_planner_interface │ │ │ ├── control_planner_interface.h │ │ │ ├── pci_manager.h │ │ │ └── pci_vehicle.h │ ├── msg │ │ ├── Path.msg │ │ └── PlannerMsgs.msg │ ├── package.xml │ └── src │ │ ├── control_planner_interface.cpp │ │ └── pci_vehicle.cpp ├── exploration_manager │ ├── CMakeLists.txt │ ├── include │ │ └── explorer │ │ │ └── explorer.h │ ├── launch │ │ ├── explorer.launch │ │ ├── robot_move.launch │ │ └── sim_env.launch │ ├── package.xml │ ├── resource │ │ └── exploration.rviz │ ├── src │ │ ├── explorer.cpp │ │ └── explorer_node.cpp │ └── worlds │ │ ├── scene_1.world │ │ ├── scene_2.world │ │ ├── scene_3.world │ │ └── scene_4.world ├── planner │ ├── CMakeLists.txt │ ├── include │ │ ├── graph │ │ │ ├── kdtree.h │ │ │ └── plan_graph.h │ │ ├── perception │ │ │ ├── grid_map_2d.h │ │ │ ├── lidar_model.h │ │ │ ├── map_2d_manager.h │ │ │ ├── map_3d.h │ │ │ └── ufomap.h │ │ ├── preprocess │ │ │ ├── preprocess.h │ │ │ ├── topo_graph.h │ │ │ └── viewpoint_manager.h │ │ ├── rapid_cover_planner │ │ │ └── rapid_cover_planner.h │ │ ├── topo_planner │ │ │ └── topo_planner.h │ │ ├── tsp_solver │ │ │ └── two_opt.h │ │ └── utils │ │ │ ├── frontier.h │ │ │ ├── point3d.h │ │ │ └── viewpoint.h │ ├── launch │ │ └── planner.launch │ ├── msg │ │ ├── EdgePair.msg │ │ ├── IdPointPair.msg │ │ ├── PreprocessMsgs.msg │ │ ├── RoadMapMsg.msg │ │ └── ViewpointsWithFrontiers.msg │ ├── package.xml │ ├── resource │ │ ├── topo_planner.rviz │ │ └── topo_planner_1.yaml │ └── src │ │ ├── graph │ │ ├── kdtree.c │ │ └── plan_graph.cpp │ │ ├── perception │ │ ├── grid_map_2d.cpp │ │ ├── lidar_model.cpp │ │ ├── map_2d_manager.cpp │ │ └── ufomap.cpp │ │ ├── preprocess │ │ ├── topo_graph.cpp │ │ └── viewpoint_manager.cpp │ │ ├── rapid_cover_planner │ │ └── rapid_cover_planner.cpp │ │ ├── topo_planner │ │ ├── topo_planner.cpp │ │ └── topo_planner_node.cpp │ │ └── tsp_solver │ │ └── two_opt.cpp ├── robot_move │ ├── cmu_planner │ │ ├── local_planner │ │ │ ├── CMakeLists.txt │ │ │ ├── launch │ │ │ │ └── local_planner.launch │ │ │ ├── package.xml │ │ │ ├── paths │ │ │ │ ├── correspondences.txt │ │ │ │ ├── pathList.ply │ │ │ │ ├── path_generator.m │ │ │ │ ├── paths.ply │ │ │ │ └── startPaths.ply │ │ │ └── src │ │ │ │ ├── localPlanner.cpp │ │ │ │ └── pathFollower.cpp │ │ └── terrain_analysis │ │ │ ├── CMakeLists.txt │ │ │ ├── launch │ │ │ └── terrain_analysis.launch │ │ │ ├── package.xml │ │ │ └── src │ │ │ └── terrainAnalysis.cpp │ ├── path_execution │ │ ├── CMakeLists.txt │ │ ├── include │ │ │ └── path_execution │ │ │ │ ├── occupancy_map_2d.h │ │ │ │ └── path_execution.h │ │ ├── launch │ │ │ └── path_execution.launch │ │ ├── package.xml │ │ └── src │ │ │ ├── occupancy_map_2d.cpp │ │ │ ├── path_execution.cpp │ │ │ └── path_execution_node.cpp │ └── traversability_analysis │ │ ├── CMakeLists.txt │ │ ├── include │ │ └── traversability_analysis │ │ │ └── terrain_map_empty.h │ │ ├── launch │ │ └── traversability_analysis_3d.launch │ │ ├── msg │ │ ├── TerrainGrid.msg │ │ └── TerrainMap.msg │ │ ├── package.xml │ │ └── src │ │ ├── online_local_map_node.cpp │ │ ├── terrain_map_empty.cpp │ │ └── traversability_analysis_node_3d.cpp ├── sensor_conversion │ ├── CMakeLists.txt │ ├── include │ │ ├── cartographer_output.h │ │ └── slam_simulation │ │ │ └── slam_output.h │ ├── package.xml │ └── src │ │ ├── sensor_odom_to_world.cpp │ │ ├── slam_output.cpp │ │ └── slam_output_node.cpp └── visualization_tools │ ├── CMakeLists.txt │ ├── include │ └── exploration_data.h │ ├── launch │ └── visualization_tools.launch │ ├── msg │ ├── ExploredVolumeTime.msg │ ├── ExploredVolumeTravedDist.msg │ ├── ExploredVolumeTravedDistTime.msg │ ├── IterationTime.msg │ ├── TravedDistTime.msg │ └── ViewpointGain.msg │ ├── package.xml │ ├── scripts │ └── realTimePlot.py │ └── src │ └── exploration_data.cpp ├── files ├── exploration_data │ └── .gitkeep └── figure │ ├── 1.jpeg │ └── 2.jpeg └── sim_env ├── 10_22outside ├── CMakeLists.txt ├── config │ └── joint_names_10_22outside.yaml ├── export.log ├── launch │ ├── display.launch │ └── gazebo.launch ├── meshes │ ├── Empty_Link.STL │ └── base_link.STL ├── package.xml └── urdf │ ├── 10_22outside.csv │ └── 10_22outside.urdf └── 10_22room2 ├── CMakeLists.txt ├── config └── joint_names_10_22room2.yaml ├── export.log ├── launch ├── display.launch └── gazebo.launch ├── meshes ├── base_link.STL ├── fixed1.STL └── fixed2.STL ├── package.xml └── urdf ├── 10_22room2.csv └── 10_22room2.urdf /.gitignore: -------------------------------------------------------------------------------- 1 | /.vscode 2 | files/exploration_data/*.txt 3 | 4 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/.clang-format: -------------------------------------------------------------------------------- 1 | BasedOnStyle: Google 2 | DerivePointerAlignment: true -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/README.md: -------------------------------------------------------------------------------- 1 | mav_comm 2 | ======== 3 | 4 | This repository contains message and service definitions used for mavs. All future message definitions go in here, existing ones in other stacks should be moved here where possible. 5 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(mav_msgs) 3 | 4 | find_package(catkin REQUIRED message_generation std_msgs geometry_msgs trajectory_msgs) 5 | include_directories(include ${catkin_INCLUDE_DIRS}) 6 | 7 | find_package(Eigen3 QUIET) 8 | if(NOT EIGEN3_FOUND) 9 | # ROS == Indigo. 10 | find_package(cmake_modules REQUIRED) 11 | find_package(Eigen REQUIRED) 12 | set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) 13 | else() 14 | # ROS > Indigo. 15 | set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) 16 | endif() 17 | 18 | add_definitions(-std=c++11) 19 | 20 | add_message_files( 21 | FILES 22 | Actuators.msg 23 | AttitudeThrust.msg 24 | RateThrust.msg 25 | RollPitchYawrateThrust.msg 26 | TorqueThrust.msg 27 | Status.msg 28 | FilteredSensorData.msg 29 | GpsWaypoint.msg 30 | ) 31 | 32 | generate_messages(DEPENDENCIES std_msgs geometry_msgs) 33 | 34 | catkin_package( 35 | INCLUDE_DIRS include ${EIGEN3_INCLUDE_DIRS} 36 | CATKIN_DEPENDS message_runtime std_msgs geometry_msgs trajectory_msgs 37 | CFG_EXTRAS export_flags.cmake 38 | ) 39 | 40 | install( 41 | DIRECTORY include/${PROJECT_NAME}/ 42 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 43 | FILES_MATCHING PATTERN "*.h" 44 | ) 45 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/cmake/export_flags.cmake: -------------------------------------------------------------------------------- 1 | SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") 2 | 3 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/include/mav_msgs/default_values.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Helen Oleynikova, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | #ifndef MAV_MSGS_DEFAULT_VALUES_H_ 22 | #define MAV_MSGS_DEFAULT_VALUES_H_ 23 | 24 | #include 25 | 26 | namespace mav_msgs { 27 | 28 | const double kZurichLatitude = 0.8267; 29 | const double kZurichHeight = 405.94; 30 | const double kGravity = MagnitudeOfGravity(kZurichHeight, kZurichLatitude); 31 | } 32 | 33 | #endif /* MAV_MSGS_DEFAULT_VALUES_H_ */ 34 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/msg/Actuators.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # This message defines lowest level commands to be sent to the actuator(s). 4 | 5 | float64[] angles # Angle of the actuator in [rad]. 6 | # E.g. servo angle of a control surface(not angle of the surface!), orientation-angle of a thruster. 7 | float64[] angular_velocities # Angular velocities of the actuator in [rad/s]. 8 | # E.g. "rpm" of rotors, propellers, thrusters 9 | float64[] normalized # Everything that does not fit the above, normalized between [-1 ... 1]. -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/msg/AttitudeThrust.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | geometry_msgs/Quaternion attitude # Attitude expressed in the header/frame_id frame. 4 | geometry_msgs/Vector3 thrust # Thrust [N] expressed in the body frame. 5 | # For a fixed-wing, usually the x-component is used. 6 | # For a multi-rotor, usually the z-component is used. 7 | # Set all un-used components to 0. 8 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/msg/FilteredSensorData.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | geometry_msgs/Vector3 accelerometer # acceleration in vehicle frame [m/s^2] 4 | geometry_msgs/Vector3 gyroscope # rotational velocity in vehicle frame [rad/s] 5 | geometry_msgs/Vector3 magnetometer # Magnetometer measurements in vehicle frame [uT] 6 | float64 barometer # Height from barometer relative to start-up point [m] 7 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/msg/GpsWaypoint.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | float64 latitude # latitude in degree 4 | float64 longitude # longitude in degree 5 | float64 altitude # above start-up point 6 | float64 heading # GPS heading 7 | float64 maxSpeed # maximum approach speed 8 | float64 maxAcc # maximum approach accelerations 9 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/msg/RateThrust.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # We use the coordinate frames with the following convention: 4 | # x: forward 5 | # y: left 6 | # z: up 7 | 8 | geometry_msgs/Vector3 angular_rates # Roll-, pitch-, yaw-rate around body axes [rad/s] 9 | geometry_msgs/Vector3 thrust # Thrust [N] expressed in the body frame. 10 | # For a fixed-wing, usually the x-component is used. 11 | # For a multi-rotor, usually the z-component is used. 12 | # Set all un-used components to 0. 13 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/msg/RollPitchYawrateThrust.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # We use the coordinate frames with the following convention: 4 | # x: forward 5 | # y: left 6 | # z: up 7 | 8 | # rotation convention (z-y'-x''): 9 | # yaw rotates around fixed frame's z axis 10 | # pitch rotates around new y-axis (y') 11 | # roll rotates around new x-axis (x'') 12 | 13 | # This is a convenience-message to support that low-level (microcontroller-based) state 14 | # estimators may not have knowledge about the absolute yaw. 15 | # Roll- and pitch-angle should be specified in the header/frame_id frame 16 | float64 roll # Roll angle [rad] 17 | float64 pitch # Pitch angle [rad] 18 | float64 yaw_rate # Yaw rate around z-axis [rad/s] 19 | 20 | geometry_msgs/Vector3 thrust # Thrust [N] expressed in the body frame. 21 | # For a fixed-wing, usually the x-component is used. 22 | # For a multi-rotor, usually the z-component is used. 23 | # Set all un-used components to 0. 24 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/msg/Status.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # If values are not known / available, set to -1 or empty string. 4 | string vehicle_name 5 | string vehicle_type # E.g. firefly, pelican ... 6 | float32 battery_voltage # Battery voltage in V. 7 | string rc_command_mode # Command mode set on the 3 position switch on the rc. 8 | bool command_interface_enabled # Reports whether the serial command interface is enabled. 9 | float32 flight_time # Flight time in s. 10 | float32 system_uptime # MAV uptime in s. 11 | float32 cpu_load # MAV CPU load: 0.0 ... 1.0 12 | 13 | string motor_status # Current motor status: running, stopped, starting, stopping. 14 | bool in_air # True if vehicle is actually in air, false otherwise 15 | 16 | string gps_status # GPS status: lock, no_lock 17 | int32 gps_num_satellites # Number of visible satellites 18 | 19 | string RC_COMMAND_ATTITUDE="attitude_thrust" 20 | string RC_COMMAND_ATTITUDE_HEIGHT="attitude_height" 21 | string RC_COMMAND_POSITION="position" 22 | 23 | string MOTOR_STATUS_RUNNING="running" 24 | string MOTOR_STATUS_STOPPED="stopped" 25 | string MOTOR_STATUS_STARTING="starting" 26 | string MOTOR_STATUS_STOPPING="stopping" 27 | 28 | string GPS_STATUS_LOCK="lock" 29 | string GPS_STATUS_NO_LOCK="no_lock" 30 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/msg/TorqueThrust.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # We use the coordinate frames with the following convention: 4 | # x: forward 5 | # y: left 6 | # z: up 7 | 8 | geometry_msgs/Vector3 torque # Torque expressed in the body frame [Nm]. 9 | geometry_msgs/Vector3 thrust # Thrust [N] expressed in the body frame. 10 | # For a fixed-wing, usually the x-component is used. 11 | # For a multi-rotor, usually the z-component is used. 12 | # Set all un-used components to 0. 13 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/mav_comm/mav_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | mav_msgs 3 | 3.3.3 4 | Package containing messages for communicating with rotary wing MAVs 5 | 6 | Rik Bähnemann 7 | 8 | Simon Lynen 9 | Markus Achtelik 10 | Pascal Gohl 11 | Sammy Omari 12 | Michael Burri 13 | Fadri Furrer 14 | Helen Oleynikova 15 | Mina Kamel 16 | Karen Bodie 17 | Rik Bähnemann 18 | 19 | ASL 2.0 20 | 21 | https://github.com/ethz-asl/mav_comm 22 | https://github.com/ethz-asl/mav_comm/issues 23 | 24 | catkin 25 | 26 | cmake_modules 27 | eigen 28 | geometry_msgs 29 | message_generation 30 | std_msgs 31 | trajectory_msgs 32 | 33 | eigen 34 | geometry_msgs 35 | message_runtime 36 | std_msgs 37 | trajectory_msgs 38 | 39 | 40 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/dependencies.rosinstall: -------------------------------------------------------------------------------- 1 | - git: {local-name: mav_comm, uri: 'git@github.com:ethz-asl/mav_comm.git'} 2 | - git: {local-name: mavlink, uri: 'git@github.com:mavlink/mavlink-gbp-release.git', version: debian/melodic/mavlink} 3 | - git: {local-name: mavros, uri: 'git@github.com:ethz-asl/mavros.git', version: 0880a97575f8c6b705096aca17ca04c6c6dcfc02} 4 | - git: {local-name: glog_catkin, uri: 'git@github.com:ethz-asl/glog_catkin.git'} 5 | - git: {local-name: mav_tools, uri: 'git@github.com:ethz-asl/mav_tools.git'} 6 | - git: {local-name: gps_umd, uri: 'git@github.com:swri-robotics/gps_umd.git'} 7 | - git: {local-name: geographic_info, uri: 'git@github.com:ros-geographic-info/geographic_info.git'} 8 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_comm/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package rotors_comm 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 2.2.3 (2018-12-13) 6 | ------------------ 7 | 8 | 2.2.2 (2018-12-12) 9 | ------------------ 10 | 11 | 2.2.0 (2018-12-10) 12 | ------------------ 13 | * switch to package format 2 14 | * Merge pull request `#397 `_ from ethz-asl/v2.1.1 15 | update to 2.1.1 16 | * Contributors: Fadri Furrer, Mina Kamel 17 | 18 | 2.1.1 (2017-04-27) 19 | ----------- 20 | * update maintainers 21 | * Contributors: fmina 22 | 23 | 2.1.0 (2017-04-08) 24 | ----------- 25 | * Return the origin of the gazebo coordinates in lat/long/alt as part of the octomap service response. 26 | * Add option to publish octomap in the ServiceCallback of the gazebo_octomap_plugin. 27 | * Adding ability to start and stop rosbag recording on command 28 | * Contributors: Fadri Furrer, Pavel, acfloria 29 | 30 | 2.0.1 (2015-08-10) 31 | ------------------ 32 | 33 | 2.0.0 (2015-08-09) 34 | ------------------ 35 | 36 | 1.1.6 (2015-06-11) 37 | ------------------ 38 | 39 | 1.1.5 (2015-06-09) 40 | ------------------ 41 | 42 | 1.1.4 (2015-05-28) 43 | ------------------ 44 | 45 | 1.1.3 (2015-05-28) 46 | ------------------ 47 | 48 | 1.1.2 (2015-05-27) 49 | ------------------ 50 | 51 | 1.1.1 (2015-04-24) 52 | ------------------ 53 | 54 | 1.1.0 (2015-04-24) 55 | ------------------ 56 | * initial Ubuntu package release 57 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_comm/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(rotors_comm) 3 | find_package(catkin REQUIRED 4 | COMPONENTS cmake_modules geometry_msgs message_generation octomap_msgs std_msgs) 5 | 6 | # Declare the service files to be built 7 | add_service_files( 8 | FILES 9 | Octomap.srv 10 | RecordRosbag.srv 11 | ) 12 | 13 | add_message_files( 14 | FILES 15 | WindSpeed.msg 16 | ) 17 | 18 | generate_messages(DEPENDENCIES geometry_msgs octomap_msgs std_msgs) 19 | 20 | catkin_package( 21 | CATKIN_DEPENDS message_runtime 22 | ) 23 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_comm/msg/WindSpeed.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | # Message should be expressed in the frame_id specified in the header. 4 | 5 | geometry_msgs/Vector3 velocity # [m/s] 6 | 7 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_comm/package.xml: -------------------------------------------------------------------------------- 1 | 2 | rotors_comm 3 | 2.2.3 4 | RotorS specific messages and services. 5 | 6 | Fadri Furrer 7 | Mina Kamel 8 | 9 | Fadri Furrer 10 | Michael Burri 11 | Mina Kamel 12 | Janosch Nikolic 13 | Markus Achtelik 14 | 15 | ASL 2.0 16 | 17 | https://github.com/ethz-asl/rotors_simulator 18 | https://github.com/ethz-asl/rotors_simulator/issues 19 | 20 | 21 | catkin 22 | 23 | cmake_modules 24 | geometry_msgs 25 | message_generation 26 | message_runtime 27 | octomap_msgs 28 | 29 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_comm/srv/Octomap.srv: -------------------------------------------------------------------------------- 1 | # The center point of the axis-aligned bounding box in the global frame 2 | geometry_msgs/Point bounding_box_origin 3 | # The 3 side lenghts of the axis-aligned bounding box 4 | geometry_msgs/Point bounding_box_lengths 5 | # The leaf size or resolution of the octomap 6 | float64 leaf_size 7 | # Indicate if the generated octomap should be published. 8 | bool publish_octomap 9 | # The filename under which the octomap should be stored (only stored if set) 10 | string filename 11 | --- 12 | # The created octomap in gazebo coordinates 13 | octomap_msgs/Octomap map 14 | # The latitude of the gazebo coordinates origin [deg] 15 | float64 origin_latitude 16 | # The longitude of the gazebo coordinates origin [deg] 17 | float64 origin_longitude 18 | # The altitude of the gazebo coordinates origin [m] 19 | float64 origin_altitude 20 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_comm/srv/RecordRosbag.srv: -------------------------------------------------------------------------------- 1 | # Whether to record the rosbag or not 2 | bool record 3 | --- 4 | bool success 5 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_control/include/rotors_control/attitude_controller.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | #ifndef ROTORS_CONTROL_ATTITUDE_CONTROLLER_H 22 | #define ROTORS_CONTROL_ATTITUDE_CONTROLLER_H 23 | 24 | #include "rotors_control/controller_base.h" 25 | #include "rotors_control/controller_factory.h" 26 | 27 | class AttitudeController : public ControllerBase { 28 | public: 29 | AttitudeController(); 30 | virtual ~AttitudeController(); 31 | virtual void InitializeParams(); 32 | virtual std::shared_ptr Clone(); 33 | virtual void CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const; 34 | 35 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 36 | private: 37 | Eigen::Matrix4Xd allocation_matrix_; 38 | Eigen::MatrixX4d angular_acc_to_rotor_velocities_; 39 | Eigen::Vector3d gain_attitude_; 40 | Eigen::Vector3d gain_angular_rate_; 41 | Eigen::Matrix3d inertia_matrix_; 42 | 43 | double mass_; 44 | const double gravity_; 45 | 46 | void ComputeDesiredAngularAcc(Eigen::Vector3d * angular_acceleration) const; 47 | 48 | }; 49 | 50 | #endif // ROTORS_CONTROL_ATTITUDE_CONTROLLER_H 51 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_control/include/rotors_control/attitude_controller_samy.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | #ifndef ROTORS_CONTROL_ATTITUDE_CONTROLLER_SAMY_H 22 | #define ROTORS_CONTROL_ATTITUDE_CONTROLLER_SAMY_H 23 | 24 | #include "rotors_control/controller_base.h" 25 | #include "rotors_control/controller_factory.h" 26 | 27 | class AttitudeControllerSamy : public ControllerBase { 28 | public: 29 | AttitudeControllerSamy(); 30 | virtual ~AttitudeControllerSamy(); 31 | virtual void InitializeParams(); 32 | virtual std::shared_ptr Clone(); 33 | virtual void CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const; 34 | 35 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 36 | private: 37 | Eigen::Matrix4Xd allocation_matrix_; 38 | Eigen::MatrixX4d angular_acc_to_rotor_velocities_; 39 | Eigen::Vector3d gain_attitude_; 40 | Eigen::Vector3d gain_angular_rate_; 41 | Eigen::Matrix3d inertia_matrix_; 42 | 43 | double mass_; 44 | const double gravity_; 45 | 46 | void ComputeDesiredAngularAcc(Eigen::Vector3d * angular_acceleration) const; 47 | 48 | }; 49 | 50 | #endif // ROTORS_CONTROL_ATTITUDE_CONTROLLER_SAMY_H 51 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_control/include/rotors_control/motor_controller.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | #ifndef ROTORS_CONTROL_MOTOR_CONTROLLER_H 22 | #define ROTORS_CONTROL_MOTOR_CONTROLLER_H 23 | 24 | #include "rotors_control/controller_base.h" 25 | #include "rotors_control/controller_factory.h" 26 | 27 | class MotorController : public ControllerBase { 28 | public: 29 | MotorController(); 30 | virtual ~MotorController(); 31 | virtual void InitializeParams(); 32 | virtual std::shared_ptr Clone(); 33 | virtual void CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const; 34 | 35 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 36 | private: 37 | Eigen::Matrix4Xd allocation_matrix_; 38 | Eigen::MatrixX4d angular_acc_to_rotor_velocities_; 39 | Eigen::Vector3d gain_attitude_; 40 | Eigen::Vector3d gain_angular_rate_; 41 | Eigen::Matrix3d inertia_matrix_; 42 | }; 43 | 44 | #endif // ROTORS_CONTROL_MOTOR_CONTROLLER_H 45 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_control/include/rotors_control/rate_controller.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | #ifndef ROTORS_CONTROL_RATE_CONTROLLER_H 22 | #define ROTORS_CONTROL_RATE_CONTROLLER_H 23 | 24 | #include "rotors_control/controller_base.h" 25 | #include "rotors_control/controller_factory.h" 26 | 27 | class RateController : public ControllerBase { 28 | public: 29 | RateController(); 30 | virtual ~RateController(); 31 | virtual void InitializeParams(); 32 | virtual std::shared_ptr Clone(); 33 | virtual void CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const; 34 | 35 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 36 | private: 37 | Eigen::Matrix4Xd allocation_matrix_; 38 | Eigen::MatrixX4d angular_acc_to_rotor_velocities_; 39 | Eigen::Vector3d gain_angular_rate_; 40 | Eigen::Matrix3d inertia_matrix_; 41 | 42 | double mass_; 43 | const double gravity_; 44 | 45 | void ComputeDesiredAngularAcc(Eigen::Vector3d * angular_acceleration) const; 46 | 47 | }; 48 | 49 | #endif // ROTORS_CONTROL_RATE_CONTROLLER_H 50 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_control/package.xml: -------------------------------------------------------------------------------- 1 | 2 | rotors_control 3 | 2.2.3 4 | RotorS control package 5 | 6 | Fadri Furrer 7 | Mina Kamel 8 | 9 | Fadri Furrer 10 | Michael Burri 11 | Mina Kamel 12 | Janosch Nikolic 13 | Markus Achtelik 14 | 15 | ASL 2.0 16 | 17 | https://github.com/ethz-asl/rotors_simulator 18 | https://github.com/ethz-asl/rotors_simulator/issues 19 | 20 | catkin 21 | 22 | cmake_modules 23 | dynamic_reconfigure 24 | geometry_msgs 25 | mav_msgs 26 | nav_msgs 27 | roscpp 28 | sensor_msgs 29 | 30 | 31 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_control/src/motor_controller.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | #include "rotors_control/motor_controller.h" 22 | 23 | MotorController::MotorController() { 24 | } 25 | 26 | MotorController::~MotorController() { 27 | } 28 | 29 | std::shared_ptr MotorController::Clone() { 30 | std::shared_ptr controller(new MotorController); 31 | return controller; 32 | } 33 | 34 | void MotorController::InitializeParams() { 35 | amount_rotors_ = 6; 36 | initialized_params_ = true; 37 | } 38 | 39 | void MotorController::CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const { 40 | assert(rotor_velocities); 41 | assert(initialized_params_); 42 | 43 | rotor_velocities->resize(amount_rotors_); 44 | 45 | *rotor_velocities = motor_reference_; 46 | } 47 | 48 | ROTORS_CONTROL_REGISTER_CONTROLLER(MotorController); 49 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_demos.rosinstall: -------------------------------------------------------------------------------- 1 | - git: {local-name: asctec_mav_framework, uri: 'https://github.com/ethz-asl/asctec_mav_framework.git'} 2 | - git: {local-name: ethzasl_msf, uri: 'https://github.com/ethz-asl/ethzasl_msf.git'} 3 | - git: {local-name: mav_comm, uri: 'https://github.com/ethz-asl/mav_comm.git'} 4 | - git: {local-name: rotors_simulator_demos, uri: 'https://github.com/ethz-asl/rotors_simulator_demos.git'} 5 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/autobackport/command.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | find . -type f -name "*.cpp" | xargs sed -i.bak -r -f autobackport/seds.txt 3 | find . -type f -name "*.h" | xargs sed -i.bak -r -f autobackport/seds.txt 4 | find . -type f -name "*.hpp" | xargs sed -i.bak -r -f autobackport/seds.txt 5 | 6 | #sed -i.bak -r -f seds_cmake.txt ../CMakeLists.txt 7 | 8 | 9 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/autobackport/commandpre7.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | if [[ "$OSTYPE" == "darwin"* ]]; then 3 | find . -type f -name "*.cpp" | xargs sed -i.bak -E -f autobackport/seds_pre7.txt 4 | find . -type f -name "*.h" | xargs sed -i.bak -E -f autobackport/seds_pre7.txt 5 | find . -type f -name "*.hpp" | xargs sed -i.bak -E -f autobackport/seds_pre7.txt 6 | else 7 | find . -type f -name "*.cpp" | xargs sed -i.bak -r -f autobackport/seds_pre7.txt 8 | find . -type f -name "*.h" | xargs sed -i.bak -r -f autobackport/seds_pre7.txt 9 | find . -type f -name "*.hpp" | xargs sed -i.bak -r -f autobackport/seds_pre7.txt 10 | fi 11 | 12 | 13 | 14 | #sed -i.bak -r -f seds_cmake.txt ../CMakeLists.txt 15 | 16 | 17 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/cmake/Findmavlink.cmake: -------------------------------------------------------------------------------- 1 | # - Try to find MAVLink 2 | # Once done, this will define 3 | # 4 | # MAVLINK_FOUND : library found 5 | # MAVLINK_INCLUDE_DIRS : include directories 6 | # MAVLINK_VERSION : version 7 | 8 | # macros 9 | include(FindPackageHandleStandardArgs) 10 | 11 | # Check for ROS_DISTRO 12 | find_program(ROSVERSION rosversion) 13 | execute_process(COMMAND ${ROSVERSION} -d 14 | OUTPUT_VARIABLE ROS_DISTRO 15 | OUTPUT_STRIP_TRAILING_WHITESPACE 16 | ) 17 | 18 | set(_MAVLINK_EXTRA_SEARCH_HINTS 19 | ${CMAKE_SOURCE_DIR}/mavlink/ 20 | ../../../mavlink/ 21 | ../../mavlink/ 22 | ${CATKIN_DEVEL_PREFIX}/ 23 | ) 24 | 25 | set(_MAVLINK_EXTRA_SEARCH_PATHS 26 | /usr/ 27 | /usr/local/ 28 | ) 29 | 30 | # look for in the hints first 31 | find_path(_MAVLINK_INCLUDE_DIR 32 | NAMES mavlink/v1.0/mavlink_types.h mavlink/v2.0/mavlink_types.h 33 | PATH_SUFFIXES include 34 | HINTS ${_MAVLINK_EXTRA_SEARCH_HINTS} 35 | NO_DEFAULT_PATH 36 | ) 37 | 38 | # look for in the hard-coded paths 39 | find_path(_MAVLINK_INCLUDE_DIR 40 | NAMES mavlink/v1.0/mavlink_types.h mavlink/v2.0/mavlink_types.h 41 | PATH_SUFFIXES include 42 | PATHS ${_MAVLINK_EXTRA_SEARCH_PATHS} 43 | NO_CMAKE_PATH 44 | NO_CMAKE_ENVIRONMENT_PATH 45 | NO_SYSTEM_ENVIRONMENT_PATH 46 | NO_CMAKE_SYSTEM_PATH 47 | ) 48 | 49 | # look specifically for the ROS version if no other was found 50 | find_path(_MAVLINK_INCLUDE_DIR 51 | NAMES mavlink/v1.0/mavlink_types.h mavlink/v2.0/mavlink_types.h 52 | PATH_SUFFIXES include 53 | PATHS /opt/ros/${ROS_DISTRO}/ 54 | ) 55 | 56 | # read the version 57 | if (EXISTS ${_MAVLINK_INCLUDE_DIR}/mavlink/config.h) 58 | file(READ ${_MAVLINK_INCLUDE_DIR}/mavlink/config.h MAVLINK_CONFIG_FILE) 59 | string(REGEX MATCH "#define MAVLINK_VERSION[ ]+\"(([0-9]+\\.)+[0-9]+)\"" 60 | _MAVLINK_VERSION_MATCH "${MAVLINK_CONFIG_FILE}") 61 | set(MAVLINK_VERSION "${CMAKE_MATCH_1}") 62 | else() 63 | set(MAVLINK_VERSION "2.0") 64 | endif() 65 | 66 | # handle arguments 67 | set(MAVLINK_INCLUDE_DIRS ${_MAVLINK_INCLUDE_DIR}) 68 | find_package_handle_standard_args( 69 | MAVLink 70 | REQUIRED_VARS MAVLINK_INCLUDE_DIRS MAVLINK_VERSION 71 | VERSION_VAR MAVLINK_VERSION 72 | ) 73 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/include/rotors_gazebo_plugins/external/gazebo_lidar_plugin.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2012-2014 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | * 16 | */ 17 | /* 18 | * Desc: Ray Plugin 19 | * Author: Nate Koenig mod by John Hsu 20 | */ 21 | 22 | #ifndef _GAZEBO_RAY_PLUGIN_HH_ 23 | #define _GAZEBO_RAY_PLUGIN_HH_ 24 | 25 | #include "gazebo/common/Plugin.hh" 26 | #include "gazebo/sensors/SensorTypes.hh" 27 | #include "gazebo/sensors/RaySensor.hh" 28 | #include "gazebo/util/system.hh" 29 | 30 | #include "Lidar.pb.h" 31 | 32 | namespace gazebo 33 | { 34 | /// \brief A Gazebo LIDAR plugin. 35 | class GAZEBO_VISIBLE GazeboLidarPlugin : public SensorPlugin 36 | { 37 | /// \brief Constructor 38 | public: GazeboLidarPlugin(); 39 | 40 | /// \brief Destructor 41 | public: virtual ~GazeboLidarPlugin(); 42 | 43 | /// \brief Update callback 44 | public: virtual void OnNewLaserScans(); 45 | 46 | /// \brief Load the plugin 47 | /// \param take in SDF root element 48 | public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf); 49 | 50 | /// \brief Pointer to parent 51 | protected: physics::WorldPtr world; 52 | 53 | /// \brief The parent sensor 54 | private: 55 | sensors::RaySensorPtr parentSensor; 56 | transport::NodePtr node_handle_; 57 | transport::PublisherPtr lidar_pub_; 58 | std::string namespace_; 59 | 60 | 61 | /// \brief The connection tied to RayPlugin::OnNewLaserScans() 62 | private: 63 | event::ConnectionPtr newLaserScansConnection; 64 | lidar_msgs::msgs::lidar lidar_message; 65 | }; 66 | } 67 | #endif 68 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/include/rotors_gazebo_plugins/geo_mag_declination.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************** 2 | * 3 | * Copyright (c) 2014 MAV GEO Library (MAVGEO). 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 7 | * are met: 8 | * 9 | * 1. Redistributions of source code must retain the above copyright 10 | * notice, this list of conditions and the following disclaimer. 11 | * 2. Redistributions in binary form must reproduce the above copyright 12 | * notice, this list of conditions and the following disclaimer in 13 | * the documentation and/or other materials provided with the 14 | * distribution. 15 | * 3. Neither the name MAVGEO nor the names of its contributors may be 16 | * used to endorse or promote products derived from this software 17 | * without specific prior written permission. 18 | * 19 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 20 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 21 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 22 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 23 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 24 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 25 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS 26 | * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED 27 | * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 28 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 29 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 30 | * POSSIBILITY OF SUCH DAMAGE. 31 | * 32 | ****************************************************************************/ 33 | 34 | /** 35 | * @file geo_mag_declination.h 36 | * 37 | * Calculation / lookup table for earth magnetic field declination. 38 | * 39 | */ 40 | 41 | #pragma once 42 | 43 | __BEGIN_DECLS 44 | 45 | float get_mag_declination(float lat, float lon); 46 | 47 | __END_DECLS 48 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/include/rotors_gazebo_plugins/motor_controller.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | 22 | #ifndef ROTORS_GAZEBO_PLUGIN_MOTOR_CONTROLLER_H 23 | #define ROTORS_GAZEBO_PLUGIN_MOTOR_CONTROLLER_H 24 | 25 | #include 26 | 27 | class MotorController 28 | { 29 | public: 30 | MotorController(int amount_motors) : 31 | ref_rotor_rot_vels_(Eigen::VectorXd::Zero(amount_motors)){}; 32 | virtual ~MotorController(); 33 | void getMotorVelocities() { 34 | calculateRefMotorVelocities(); 35 | return ref_rotor_rot_vels_; 36 | } 37 | 38 | virtual void calculateRefMotorVelocities() = 0; 39 | virtual void initializeParams() = 0; 40 | virtual void publish() = 0; 41 | 42 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 43 | protected: 44 | // imu_ 45 | // odom_ 46 | 47 | Eigen::Vector3d position_; 48 | Eigen::Vector3d velocity_; 49 | Eigen::Quaternion attitude_; 50 | Eigen::VectorXd ref_rotor_rot_vels_; 51 | }; 52 | 53 | #endif // ROTORS_GAZEBO_PLUGIN_MOTOR_CONTROLLER_H 54 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/include/rotors_gazebo_plugins/motor_model.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | 22 | #ifndef ROTORS_GAZEBO_PLUGINS_MOTOR_MODEL_H 23 | #define ROTORS_GAZEBO_PLUGINS_MOTOR_MODEL_H 24 | 25 | #include 26 | 27 | class MotorModel 28 | { 29 | public: 30 | MotorModel() 31 | : motor_rot_vel_(0.0), 32 | ref_motor_rot_vel_(0.0), 33 | prev_sim_time_(0.0), 34 | sampling_time_(0.01) {} 35 | virtual ~MotorModel() {} 36 | void GetMotorVelocity(double &result) const { 37 | result = motor_rot_vel_; 38 | } 39 | void SetReferenceMotorVelocity(double ref_motor_rot_vel) { 40 | ref_motor_rot_vel_ = ref_motor_rot_vel; 41 | } 42 | 43 | virtual void InitializeParams() = 0; 44 | virtual void Publish() = 0; 45 | 46 | protected: 47 | double motor_rot_vel_; 48 | double ref_motor_rot_vel_; 49 | double prev_ref_motor_rot_vel_; 50 | double prev_sim_time_; 51 | double sampling_time_; 52 | 53 | 54 | virtual void UpdateForcesAndMoments() = 0; 55 | }; 56 | 57 | #endif // ROTORS_GAZEBO_PLUGINS_MOTOR_MODEL_H 58 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/include/rotors_gazebo_plugins/msgbuffer.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief MAVConn message buffer class (internal) 3 | * @file msgbuffer.h 4 | * @author Vladimir Ermakov 5 | * @author Amy Wagoner (adaptation to Gazebo) 6 | */ 7 | /** 8 | * Copyright 2017 MAVROS dev team. All rights reserved. 9 | * 10 | * Licensed under the Apache License, Version 2.0 (the "License"); 11 | * you may not use this file except in compliance with the License. 12 | * You may obtain a copy of the License at 13 | * 14 | * http://www.apache.org/licenses/LICENSE-2.0 15 | * 16 | * Unless required by applicable law or agreed to in writing, software 17 | * distributed under the License is distributed on an "AS IS" BASIS, 18 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 19 | * See the License for the specific language governing permissions and 20 | * limitations under the License. 21 | */ 22 | 23 | #pragma once 24 | 25 | #include 26 | #include "mavlink/v2.0/common/mavlink.h" 27 | 28 | namespace gazebo { 29 | /** 30 | * @brief Message buffer for internal use in libmavconn 31 | */ 32 | struct MsgBuffer { 33 | //! Maximum buffer size with padding for CRC bytes (280 + padding) 34 | static constexpr ssize_t MAX_SIZE = MAVLINK_MAX_PACKET_LEN + 16; 35 | uint8_t data[MAX_SIZE]; 36 | ssize_t len; 37 | ssize_t pos; 38 | 39 | MsgBuffer() : 40 | pos(0), 41 | len(0) 42 | { } 43 | 44 | /** 45 | * @brief Buffer constructor from mavlink_message_t 46 | */ 47 | explicit MsgBuffer(const mavlink_message_t *msg) : 48 | pos(0) 49 | { 50 | len = mavlink_msg_to_send_buffer(data, msg); 51 | // paranoic check, it must be less than MAVLINK_MAX_PACKET_LEN 52 | assert(len < MAX_SIZE); 53 | } 54 | 55 | /** 56 | * @brief Buffer constructor for send_bytes() 57 | * @param[in] nbytes should be less than MAX_SIZE 58 | */ 59 | MsgBuffer(const uint8_t *bytes, ssize_t nbytes) : 60 | pos(0), 61 | len(nbytes) 62 | { 63 | assert(0 < nbytes && nbytes < MAX_SIZE); 64 | memcpy(data, bytes, nbytes); 65 | } 66 | 67 | virtual ~MsgBuffer() { 68 | pos = 0; 69 | len = 0; 70 | } 71 | 72 | uint8_t *dpos() { 73 | return data + pos; 74 | } 75 | 76 | ssize_t nbytes() { 77 | return len - pos; 78 | } 79 | }; 80 | } // namespace gazebo 81 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/include/rotors_gazebo_plugins/sdf_api_wrapper.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 3 | * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 4 | * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 5 | * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 6 | * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 7 | * 8 | * Licensed under the Apache License, Version 2.0 (the "License"); 9 | * you may not use this file except in compliance with the License. 10 | * You may obtain a copy of the License at 11 | * 12 | * http://www.apache.org/licenses/LICENSE-2.0 13 | 14 | * Unless required by applicable law or agreed to in writing, software 15 | * distributed under the License is distributed on an "AS IS" BASIS, 16 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 17 | * See the License for the specific language governing permissions and 18 | * limitations under the License. 19 | */ 20 | 21 | 22 | #ifndef ROTORS_GAZEBO_PLUGINS_SDF_API_WRAPPER_H 23 | #define ROTORS_GAZEBO_PLUGINS_SDF_API_WRAPPER_H 24 | 25 | #include 26 | 27 | namespace gazebo { 28 | 29 | #if SDF_MAJOR_VERSION >= 3 30 | typedef ignition::math::Vector3d SdfVector3; 31 | #else 32 | class SdfVector3 : public sdf::Vector3 { 33 | /* 34 | A wrapper class for deprecated sdf::Vector3 class to provide the same accessor 35 | functions as in the newer ignition::math::Vector3 class. 36 | */ 37 | 38 | public: 39 | using sdf::Vector3::Vector3; 40 | virtual ~SdfVector3() {} 41 | 42 | /// \brief Get the x value 43 | /// \return the x value 44 | double X() { return this->x; } 45 | 46 | /// \brief Get the y value 47 | /// \return the y value 48 | double Y() { return this->y; } 49 | 50 | /// \brief Get the z value 51 | /// \return the z value 52 | double Z() { return this->z; } 53 | }; 54 | #endif 55 | } 56 | 57 | #endif // ROTORS_GAZEBO_PLUGINS_SDF_API_WRAPPER_H 58 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Actuators.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_sensor_msgs; 3 | 4 | import "Header.proto"; 5 | 6 | // Actuators message type which is emitted by 7 | // GazeboMultirotorBasePlugin 8 | message Actuators 9 | { 10 | required gz_std_msgs.Header header = 1; 11 | 12 | repeated double angles = 2 [packed=true]; 13 | 14 | repeated double angular_velocities = 3 [packed=true]; 15 | 16 | repeated double normalized = 4 [packed=true]; 17 | } 18 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/CommandMotorSpeed.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_mav_msgs; 3 | 4 | message CommandMotorSpeed { 5 | repeated float motor_speed = 1 [packed=true]; 6 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/ConnectGazeboToRosTopic.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_std_msgs; 3 | 4 | // Message designed to be sent to the ROS interface plugin by other 5 | // Gazebo plugins, to tell it to forward messages on a particular Gazebo topic onto 6 | // a ROS topic 7 | message ConnectGazeboToRosTopic 8 | { 9 | 10 | //required string gazebo_namespace = 1; 11 | required string gazebo_topic = 2; 12 | required string ros_topic = 3; 13 | 14 | // The supported messages types that the ROS interface plugin knows to convert 15 | // from a Gazebo to a ROS message. 16 | // Provided to gz_std_msgs::ConnectGazeboToRosTopic::set_msgtype() 17 | enum MsgType { 18 | ACTUATORS = 0; 19 | FLOAT_32 = 1; 20 | FLUID_PRESSURE = 2; 21 | IMU = 3; 22 | JOINT_STATE = 4; 23 | MAGNETIC_FIELD = 5; 24 | NAV_SAT_FIX = 6; 25 | ODOMETRY = 7; 26 | POSE = 8; 27 | POSE_WITH_COVARIANCE_STAMPED = 9; 28 | TRANSFORM_STAMPED = 10; 29 | TWIST_STAMPED = 11; 30 | VECTOR_3D_STAMPED = 12; 31 | WIND_SPEED = 13; 32 | WRENCH_STAMPED = 14; 33 | } 34 | required MsgType msgType = 4; 35 | } 36 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/ConnectRosToGazeboTopic.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_std_msgs; 3 | 4 | // Message designed to be sent to the ROS interface plugin by other 5 | // Gazebo plugins, to tell it to forward messages on a particular ROS topic onto 6 | // a Gazebo topic 7 | message ConnectRosToGazeboTopic 8 | { 9 | required string ros_topic = 1; 10 | //required string gazebo_namespace = 2; 11 | required string gazebo_topic = 3; 12 | 13 | // The supported messages types that the ROS interface plugin knows to convert 14 | // from a ROS to a Gazebo message 15 | enum MsgType { 16 | ACTUATORS = 0; 17 | COMMAND_MOTOR_SPEED = 1; 18 | ROLL_PITCH_YAWRATE_THRUST = 2; 19 | WIND_SPEED = 3; 20 | } 21 | required MsgType msgType = 4; 22 | } 23 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Float32.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_std_msgs; 3 | 4 | // Holds a single 32-bit float 5 | message Float32 { 6 | required float data = 1; 7 | } 8 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/FluidPressure.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_sensor_msgs; 3 | 4 | import "Header.proto"; 5 | 6 | // FluidPressure message type which is emitted by the 7 | // Pressure Gazebo plugin 8 | // Designed to imitate ROS sensor_msgs::FluidPressure 9 | message FluidPressure 10 | { 11 | required gz_std_msgs.Header header = 1; 12 | 13 | required double fluid_pressure = 2; 14 | 15 | required double variance = 3; 16 | } 17 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Header.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_std_msgs; 3 | 4 | // Header type designed to be added to other 5 | // Gazebo message types. 6 | message Header { 7 | message Stamp { 8 | required uint32 sec = 1; 9 | required uint32 nsec = 2; 10 | } 11 | required string frame_id = 1; 12 | required Stamp stamp = 2; 13 | } 14 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Imu.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_sensor_msgs; 3 | 4 | import "quaternion.proto"; 5 | import "vector3d.proto"; 6 | import "Header.proto"; 7 | 8 | // Message published by GazeboImuPlugin. 9 | message Imu 10 | { 11 | 12 | required gz_std_msgs.Header header = 1; 13 | 14 | required gazebo.msgs.Quaternion orientation = 2; 15 | repeated float orientation_covariance = 3 [packed=true]; 16 | 17 | required gazebo.msgs.Vector3d angular_velocity = 4; 18 | repeated float angular_velocity_covariance = 5 [packed=true]; 19 | 20 | required gazebo.msgs.Vector3d linear_acceleration = 6; 21 | repeated float linear_acceleration_covariance = 7 [packed=true]; 22 | } 23 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/JointState.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_sensor_msgs; 3 | 4 | import "Header.proto"; 5 | 6 | // JointState message type which is emitted by 7 | // GazeboMultirotorBasePlugin 8 | message JointState 9 | { 10 | required gz_std_msgs.Header header = 1; 11 | 12 | repeated string name = 2; 13 | repeated double position = 3 [packed=true]; 14 | 15 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Lidar.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package lidar_msgs.msgs; 3 | 4 | message lidar 5 | { 6 | required float time_msec = 1; 7 | required float min_distance = 2; 8 | required float max_distance = 3; 9 | required float current_distance = 4; 10 | } 11 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/MagneticField.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_sensor_msgs; 3 | 4 | import "quaternion.proto"; 5 | import "vector3d.proto"; 6 | import "Header.proto"; 7 | 8 | // Magnetic field message type which is emitted by the 9 | // Magnetometer Gazebo plugin 10 | message MagneticField 11 | { 12 | 13 | required gz_std_msgs.Header header = 1; 14 | 15 | required gazebo.msgs.Vector3d magnetic_field = 2; 16 | 17 | repeated float magnetic_field_covariance = 3 [packed=true]; 18 | } 19 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/NavSatFix.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_sensor_msgs; 3 | 4 | import "Header.proto"; 5 | 6 | // NavSatFix (GPS) message type which is emitted by the 7 | // GPS Gazebo plugin 8 | // Designed to imitate ROS sensor_msgs::NavSatStatus 9 | message NavSatFix 10 | { 11 | required gz_std_msgs.Header header = 1; 12 | 13 | enum Service { 14 | SERVICE_GPS = 0; 15 | SERVICE_GLONASS = 1; 16 | SERVICE_COMPASS = 2; 17 | SERVICE_GALILEO = 3; 18 | } 19 | required Service service = 2; 20 | 21 | enum Status { 22 | STATUS_NO_FIX = 0; 23 | STATUS_FIX = 1; 24 | STATUS_SBAS_FIX = 2; 25 | STATUS_GBAS_FIX = 3; 26 | } 27 | required Status status = 3; 28 | 29 | required double latitude = 4; 30 | required double longitude = 5; 31 | required double altitude = 6; 32 | 33 | enum PositionCovarianceType { 34 | COVARIANCE_TYPE_UNKNOWN = 0; 35 | COVARIANCE_TYPE_APPROXIMATED = 1; 36 | COVARIANCE_TYPE_DIAGONAL_KNOWN = 2; 37 | COVARIANCE_TYPE_KNOWN = 3; 38 | } 39 | required PositionCovarianceType position_covariance_type = 7; 40 | 41 | repeated float position_covariance = 8 [packed=true]; 42 | 43 | } 44 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Odometry.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "PoseWithCovariance.proto"; 6 | import "TwistWithCovariance.proto"; 7 | 8 | // Odometry message type which is emitted by 9 | // GazeboMultirotorBasePlugin 10 | message Odometry 11 | { 12 | required gz_std_msgs.Header header = 1; 13 | 14 | required string child_frame_id = 2; 15 | required PoseWithCovariance pose = 3; 16 | required TwistWithCovariance twist = 4; 17 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/OpticalFlow.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package opticalFlow_msgs.msgs; 3 | 4 | message opticalFlow 5 | { 6 | required float time_usec = 1; 7 | required float sensor_id = 2; 8 | required float integration_time_us = 3; 9 | required float integrated_x = 4; 10 | required float integrated_y = 5; 11 | required float integrated_xgyro = 6; 12 | required float integrated_ygyro = 7; 13 | required float integrated_zgyro = 8; 14 | required float temperature = 9; 15 | required float quality = 10; 16 | required float time_delta_distance_us = 11; 17 | required float distance = 12; 18 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Point.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | // Point (x, y, z) message type which designed to be used 5 | // in other message types 6 | message Point 7 | { 8 | required double x = 1; 9 | required double y = 2; 10 | required double z = 3; 11 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/PointStamped.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "Point.proto"; 6 | 7 | // PointStamped message type 8 | message PointStamped 9 | { 10 | required gz_std_msgs.Header header = 1; 11 | required Point point = 2; 12 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/PoseStamped.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "pose.proto"; 6 | 7 | // PoseStamped message type which is emitted by 8 | // GazeboOdometryPlugin 9 | message PoseStamped 10 | { 11 | required gz_std_msgs.Header header = 1; 12 | required gazebo.msgs.Pose pose = 2; 13 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/PoseWithCovariance.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "pose.proto"; 5 | 6 | // Pose with covariance message type which designed to be used 7 | // in other message types 8 | message PoseWithCovariance { 9 | required gazebo.msgs.Pose pose = 1; 10 | repeated double covariance = 2 [packed=true]; 11 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/PoseWithCovarianceStamped.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "PoseWithCovariance.proto"; 6 | 7 | // Pose with covariance stamped message type, 8 | // used to emulate a ROS message in the Gazebo framework. 9 | message PoseWithCovarianceStamped { 10 | required gz_std_msgs.Header header = 1; 11 | required PoseWithCovariance pose_with_covariance = 2; 12 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/RollPitchYawrateThrust.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_mav_msgs; 3 | 4 | import "Header.proto"; 5 | import "vector3d.proto"; 6 | 7 | message RollPitchYawrateThrust { 8 | required gz_std_msgs.Header header = 1; 9 | 10 | // We use the coordinate frames with the following convention: 11 | // x: forward 12 | // y: left 13 | // z: up 14 | 15 | // rotation convention (z-y'-x''): 16 | // yaw rotates around fixed frame's z axis 17 | // pitch rotates around new y-axis (y') 18 | // roll rotates around new x-axis (x'') 19 | required double roll = 2; 20 | required double pitch = 3; 21 | required double yaw_rate = 4; 22 | 23 | // Thrust [N] expressed in the body frame. 24 | // For a fixed-wing, usually the x-component is used. 25 | // For a multi-rotor, usually the z-component is used. 26 | // Set all un-used components to 0. 27 | required gazebo.msgs.Vector3d thrust = 5; 28 | } 29 | 30 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Transform.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "vector3d.proto"; 5 | import "quaternion.proto"; 6 | 7 | message Transform { 8 | required gazebo.msgs.Vector3d translation = 1; 9 | required gazebo.msgs.Quaternion rotation = 2; 10 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/TransformStamped.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "Transform.proto"; 6 | 7 | message TransformStamped { 8 | required gz_std_msgs.Header header = 1; 9 | required Transform transform = 2; 10 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/TransformStampedWithFrameIds.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "Transform.proto"; 6 | 7 | // A stamped transform message, but also with the 8 | // parent and child frame ids. Note that the parent frame ID 9 | // is likely to be the same as the frame_id provided in the 10 | // header. Used by the topic to send transforms from the odometry 11 | // plugin to the ROS interface plugin, so it can then call 12 | // transform_broadcast(). 13 | message TransformStampedWithFrameIds { 14 | required gz_std_msgs.Header header = 1; 15 | required Transform transform = 2; 16 | required string parent_frame_id = 3; 17 | required string child_frame_id = 4; 18 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Twist.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "vector3d.proto"; 5 | 6 | // Twist message type incorporates linear 7 | // and angular components. 8 | message Twist 9 | { 10 | required gazebo.msgs.Vector3d linear = 1; 11 | required gazebo.msgs.Vector3d angular = 2; 12 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/TwistStamped.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "Twist.proto"; 6 | 7 | // TwistStamped (e.g. ground speed) message type which is emitted by the 8 | // GPS Gazebo plugin 9 | message TwistStamped 10 | { 11 | required gz_std_msgs.Header header = 1; 12 | required Twist twist = 2; 13 | } 14 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/TwistWithCovariance.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Twist.proto"; 5 | 6 | // Twist with covariance message type which is designed to be used 7 | // in other message types 8 | message TwistWithCovariance { 9 | required Twist twist = 1; 10 | repeated double covariance = 2 [packed=true]; 11 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Vector3dStamped.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "vector3d.proto"; 6 | 7 | // Extends the Gazebo Vector3d message type to 8 | // include a header. 9 | message Vector3dStamped 10 | { 11 | required gz_std_msgs.Header header = 1; 12 | required gazebo.msgs.Vector3d position = 2; 13 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/WindSpeed.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_mav_msgs; 3 | 4 | import "Header.proto"; 5 | import "vector3d.proto"; 6 | 7 | message WindSpeed { 8 | required gz_std_msgs.Header header = 1; 9 | required gazebo.msgs.Vector3d velocity = 2; 10 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/Wrench.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "vector3d.proto"; 5 | 6 | // Wrench includes both force and torque information about a joint. 7 | message Wrench 8 | { 9 | required gazebo.msgs.Vector3d force = 1; 10 | required gazebo.msgs.Vector3d torque = 2; 11 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/msgs/WrenchStamped.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto2"; 2 | package gz_geometry_msgs; 3 | 4 | import "Header.proto"; 5 | import "Wrench.proto"; 6 | 7 | // A message with both a header (with time info) and wrench info (forces and torques). 8 | message WrenchStamped { 9 | required gz_std_msgs.Header header = 1; 10 | required Wrench wrench = 2; 11 | } -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_gazebo_plugins/package.xml: -------------------------------------------------------------------------------- 1 | 2 | rotors_gazebo_plugins 3 | 2.2.3 4 | The rotors_gazebo_plugins package 5 | 6 | Fadri Furrer 7 | Michael Pantic 8 | Mina Kamel 9 | 10 | Fadri Furrer 11 | Michael Burri 12 | Mina Kamel 13 | Janosch Nikolic 14 | Markus Achtelik 15 | 16 | ASL 2.0 17 | 18 | https://github.com/ethz-asl/rotors_simulator 19 | https://github.com/ethz-asl/rotors_simulator/issues 20 | 21 | catkin 22 | 23 | 24 | cmake_modules 25 | cv_bridge 26 | gazebo 27 | gazebo_plugins 28 | gazebo_ros 29 | geometry_msgs 30 | libgoogle-glog-dev 31 | protobuf-dev 32 | mavros 33 | mav_msgs 34 | octomap_msgs 35 | octomap_ros 36 | octomap 37 | rosbag 38 | roscpp 39 | rotors_comm 40 | rotors_control 41 | std_srvs 42 | tf 43 | yaml-cpp 44 | 45 | 46 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_hil.rosinstall: -------------------------------------------------------------------------------- 1 | - git: {local-name: mav_comm, uri: 'https://github.com/ethz-asl/mav_comm.git'} 2 | - git: {local-name: mavlink, uri: 'https://github.com/mavlink/mavlink-gbp-release.git', version: 'upstream'} 3 | -------------------------------------------------------------------------------- /3rdparty/fly_sim/rotors_fly/rotors_minimal.rosinstall: -------------------------------------------------------------------------------- 1 | - git: {local-name: mav_comm, uri: 'https://github.com/ethz-asl/mav_comm.git'} 2 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(jackal_control) 3 | 4 | find_package(catkin REQUIRED COMPONENTS roslaunch) 5 | 6 | catkin_package() 7 | 8 | roslaunch_add_file_check(launch/control.launch) 9 | roslaunch_add_file_check(launch/teleop.launch) 10 | 11 | install(DIRECTORY config launch 12 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 13 | ) 14 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/config/control.yaml: -------------------------------------------------------------------------------- 1 | jackal_joint_publisher: 2 | type: "joint_state_controller/JointStateController" 3 | publish_rate: 50 4 | 5 | jackal_velocity_controller: 6 | type: "diff_drive_controller/DiffDriveController" 7 | left_wheel: ['front_left_wheel', 'rear_left_wheel'] 8 | right_wheel: ['front_right_wheel', 'rear_right_wheel'] 9 | publish_rate: 50 10 | pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03] 11 | twist_covariance_diagonal: [0.001, 0.001, 0.001, 1000000.0, 1000000.0, 0.03] 12 | cmd_vel_timeout: 0.25 13 | 14 | k_l: 0.1 15 | k_r: 0.1 16 | 17 | # Odometry fused with IMU is published by robot_localization, so 18 | # no need to publish a TF based on encoders alone. 19 | enable_odom_tf: false 20 | 21 | # Wheel separation and radius multipliers 22 | wheel_separation_multiplier: 1.5 # default: 1.0 23 | wheel_radius_multiplier : 1.0 # default: 1.0 24 | 25 | # Velocity and acceleration limits 26 | # Whenever a min_* is unspecified, default to -max_* 27 | linear: 28 | x: 29 | has_velocity_limits : true 30 | max_velocity : 2.0 # m/s 31 | has_acceleration_limits: true 32 | max_acceleration : 20.0 # m/s^2 33 | angular: 34 | z: 35 | has_velocity_limits : true 36 | max_velocity : 4.0 # rad/s 37 | has_acceleration_limits: true 38 | max_acceleration : 25.0 # rad/s^2 39 | 40 | 41 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/config/robot_localization.yaml: -------------------------------------------------------------------------------- 1 | #Configuation for robot odometry EKF 2 | # 3 | frequency: 50 4 | 5 | odom0: /jackal_velocity_controller/odom 6 | odom0_config: [false, false, false, 7 | false, false, false, 8 | true, true, true, 9 | false, false, true, 10 | false, false, false] 11 | odom0_differential: false 12 | 13 | imu0: /imu/data 14 | imu0_config: [false, false, false, 15 | true, true, true, 16 | false, false, false, 17 | true, true, true, 18 | false, false, false] 19 | imu0_differential: false 20 | 21 | odom_frame: odom 22 | base_link_frame: base_link 23 | world_frame: odom 24 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/config/teleop.yaml: -------------------------------------------------------------------------------- 1 | # Teleop configuration for PS3 Navigation joystick. 2 | teleop_twist_joy: 3 | axis_linear: 1 4 | scale_linear: 0.4 5 | scale_linear_turbo: 2.0 6 | axis_angular: 0 7 | scale_angular: 1.4 8 | enable_button: 8 9 | enable_turbo_button: 10 10 | joy_node: 11 | deadzone: 0.1 12 | autorepeat_rate: 20 13 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/config/teleop_ps4.yaml: -------------------------------------------------------------------------------- 1 | # Teleop configuration for PS4 joystick using the x-pad configuration. 2 | teleop_twist_joy: 3 | axis_linear: 1 4 | scale_linear: 0.4 5 | scale_linear_turbo: 2.0 6 | axis_angular: 0 7 | scale_angular: 1.4 8 | enable_button: 4 9 | enable_turbo_button: 5 10 | joy_node: 11 | deadzone: 0.1 12 | autorepeat_rate: 20 13 | dev: /dev/input/ds4x 14 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/config/twist_mux.yaml: -------------------------------------------------------------------------------- 1 | topics: 2 | - name : joy 3 | topic : joy_teleop/cmd_vel 4 | timeout : 0.5 5 | priority: 10 6 | - name : bt_joy 7 | topic : bluetooth_teleop/cmd_vel 8 | timeout : 0.5 9 | priority: 9 10 | - name : interactive_marker 11 | topic : twist_marker_server/cmd_vel 12 | timeout : 0.5 13 | priority: 8 14 | - name : external 15 | topic : cmd_vel 16 | timeout : 0.5 17 | priority: 1 18 | locks: 19 | - name : e_stop 20 | topic : e_stop 21 | timeout : 0.0 22 | priority: 255 23 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/launch/control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/launch/teleop.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 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_control/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | jackal_control 4 | 0.6.5 5 | Controllers for Jackal 6 | Mike Purvis 7 | 8 | BSD 9 | 10 | http://wiki.ros.org/jackal_control 11 | Mike Purvis 12 | 13 | catkin 14 | roslaunch 15 | controller_manager 16 | interactive_marker_twist_server 17 | diff_drive_controller 18 | joint_state_controller 19 | joy 20 | robot_localization 21 | teleop_twist_joy 22 | topic_tools 23 | twist_mux 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(jackal_description) 3 | 4 | find_package(catkin REQUIRED COMPONENTS roslaunch) 5 | 6 | catkin_package() 7 | 8 | roslaunch_add_file_check(launch/description.launch) 9 | 10 | install(DIRECTORY meshes launch urdf 11 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 12 | ) 13 | 14 | if(WIN32) 15 | install(PROGRAMS scripts/env_run.bat 16 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 17 | ) 18 | else() 19 | install(PROGRAMS scripts/env_run 20 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 21 | ) 22 | endif() 23 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/launch/description.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/accessory_fender.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/accessory_fender.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/ark_enclosure.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/ark_enclosure.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/bridge-plate.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/bridge-plate.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/camera-beam.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/camera-beam.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/camera-bracket.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/camera-bracket.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/hokuyo_ust10.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/hokuyo_ust10.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/jackal-base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/jackal-base.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/jackal-fender.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/jackal-fender.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/jackal-fenders.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/jackal-fenders.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/jackal-wheel.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/jackal-wheel.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/novatel-smart6.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/novatel-smart6.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/sick-lms1xx-bracket.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/sick-lms1xx-bracket.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/stereo-camera-beam.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/stereo-camera-beam.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/meshes/stereo-camera-bracket.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_description/meshes/stereo-camera-bracket.stl -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | jackal_description 4 | 0.6.5 5 | URDF robot description for Jackal 6 | 7 | Mike Purvis 8 | 9 | BSD 10 | 11 | Mike Purvis 12 | 13 | catkin 14 | roslaunch 15 | robot_state_publisher 16 | urdf 17 | xacro 18 | lms1xx 19 | pointgrey_camera_description 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/scripts/env_run: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # This simple wrapper allowing us to pass a set of 3 | # environment variables to be sourced prior to running 4 | # another command. Used in the launch file for setting 5 | # robot configurations prior to xacro. 6 | 7 | ENVVARS_FILE=$1 8 | shift 1 9 | 10 | set -a 11 | source $ENVVARS_FILE 12 | $@ 13 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/scripts/env_run.bat: -------------------------------------------------------------------------------- 1 | @echo off 2 | setlocal 3 | REM This simple wrapper allowing us to pass a set of 4 | REM environment variables to be sourced prior to running 5 | REM another command. Used in the launch file for setting 6 | REM robot configurations prior to xacro. 7 | 8 | set ENVVARS_FILE=%1 9 | 10 | REM get arguments starting from %2 11 | shift 12 | set RUNNER_COMMAND= 13 | :getrunnerloop 14 | if "%1"=="" goto after_loop 15 | if "%RUNNER_COMMAND%" == "" ( 16 | set RUNNER_COMMAND=%1 17 | ) else ( 18 | set RUNNER_COMMAND=%RUNNER_COMMAND% %1 19 | ) 20 | shift 21 | goto getrunnerloop 22 | 23 | :after_loop 24 | call %ENVVARS_FILE% 25 | call %RUNNER_COMMAND% 26 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/accessories/bridge_plate.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 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/accessories/camera_mount.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 | Gazebo/DarkGrey 33 | 34 | 35 | 36 | Gazebo/DarkGrey 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/accessories/novatel_smart6.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/accessories/standoffs.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 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/accessories/stereo_camera_mount.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 | Gazebo/DarkGrey 41 | 42 | 43 | 44 | Gazebo/DarkGrey 45 | 46 | 47 | 48 | 49 | 50 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/configs/base: -------------------------------------------------------------------------------- 1 | # The base Jackal configuration has no accessories at all, 2 | # so nothing need be specified here; the defaults as given 3 | # in the URDF suffice to define this config. 4 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/configs/base.bat: -------------------------------------------------------------------------------- 1 | @echo off 2 | 3 | REM The base Jackal configuration has no accessories at all, 4 | REM so nothing need be specified here; the defaults as given 5 | REM in the URDF suffice to define this config. 6 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/configs/front_bumblebee2: -------------------------------------------------------------------------------- 1 | 2 | JACKAL_BB2=1 3 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/configs/front_bumblebee2.bat: -------------------------------------------------------------------------------- 1 | @echo off 2 | 3 | set JACKAL_BB2=1 4 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/configs/front_flea3: -------------------------------------------------------------------------------- 1 | 2 | JACKAL_FLEA3=1 3 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/configs/front_flea3.bat: -------------------------------------------------------------------------------- 1 | @echo off 2 | 3 | set JACKAL_FLEA3=1 4 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/configs/front_laser: -------------------------------------------------------------------------------- 1 | # The front_laser configuration of Jackal is sufficient for 2 | # basic gmapping and navigation. It is mostly the default 3 | # config, but with a SICK LMS100 series LIDAR on the front, 4 | # pointing forward. 5 | 6 | JACKAL_LASER=1 7 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/configs/front_laser.bat: -------------------------------------------------------------------------------- 1 | @echo off 2 | 3 | REM The front_laser configuration of Jackal is sufficient for 4 | REM basic gmapping and navigation. It is mostly the default 5 | REM config, but with a SICK LMS100 series LIDAR on the front, 6 | REM pointing forward. 7 | 8 | set JACKAL_LASER=1 9 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_description/urdf/empty.urdf: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package jackal_gazebo 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.0 (2015-01-20) 6 | ------------------ 7 | * Add small hack to continue supporting the front_laser:=true arg, since that was prominently documented. 8 | * Change from individual accessory args to a single "config" arg. 9 | * Contributors: Mike Purvis 10 | 11 | 0.2.3 (2014-12-12) 12 | ------------------ 13 | * Added jackal_race world. 14 | * Add hector_gazebo_plugins dependency. 15 | * Contributors: Mike Purvis, spourmehr 16 | 17 | 0.2.2 (2014-09-10) 18 | ------------------ 19 | * Add author tags. 20 | * Added launch arg to enable front-facing laser. 21 | * Contributors: Mike Purvis 22 | 23 | 0.2.1 (2014-09-10) 24 | ------------------ 25 | * Install all directories. 26 | * Contributors: Mike Purvis 27 | 28 | 0.2.0 (2014-09-09) 29 | ------------------ 30 | * Default world for Jackal sim is now a green one. 31 | * Add missing dependencies on Gazebo plugin packages. 32 | * Contributors: Mike Purvis 33 | 34 | 0.1.0 (2014-09-07) 35 | ------------------ 36 | * Initial version 37 | * Contributors: Mike Purvis 38 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(jackal_gazebo) 3 | 4 | find_package(catkin REQUIRED COMPONENTS roslaunch) 5 | 6 | catkin_package() 7 | 8 | roslaunch_add_file_check(launch/jackal_world.launch) 9 | 10 | install(DIRECTORY launch Media worlds 11 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 12 | ) 13 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/Media/models/textures/Vegetation_Grass1.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_gazebo/Media/models/textures/Vegetation_Grass1.jpg -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/Media/models/textures/mtt.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_gazebo/Media/models/textures/mtt.png -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/Media/models/textures/texture0.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_gazebo/Media/models/textures/texture0.jpg -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/Media/models/textures/texture0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/jackal/jackal_gazebo/Media/models/textures/texture0.png -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/launch/jackal_model.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 9 | 10 | 11 | 12 | 13 | 14 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/launch/jackal_world.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 12 | 13 | 14 | 15 | 16 | 17 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 41 | 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | jackal_gazebo 4 | 0.3.0 5 | Launchfiles to use Jackal in Gazebo. 6 | 7 | Mike Purvis 8 | Mike Purvis 9 | 10 | BSD 11 | 12 | http://wiki.ros.org/jackal_gazebo 13 | 14 | catkin 15 | roslaunch 16 | gazebo_ros 17 | gazebo_ros_control 18 | gazebo_plugins 19 | hector_gazebo_plugins 20 | jackal_control 21 | jackal_description 22 | 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_gazebo/worlds/empty.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://sun 7 | 8 | 9 | 10 | model://ground_plane 11 | 12 | 13 | model://asphalt_plane 14 | 15 | 16 | 18 | 19 | 20 | 21 | 0 0 -9.8066 22 | 23 | 24 | quick 25 | 10 26 | 1.3 27 | 0 28 | 29 | 30 | 0 31 | 0.2 32 | 100 33 | 0.001 34 | 35 | 36 | 0.002 37 | 1 38 | 500 39 | 6e-06 2.3e-05 -4.2e-05 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package jackal_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.6.5 (2020-04-20) 6 | ------------------ 7 | 8 | 0.6.4 (2020-03-04) 9 | ------------------ 10 | 11 | 0.6.3 (2019-07-18) 12 | ------------------ 13 | 14 | 0.6.2 (2019-04-18) 15 | ------------------ 16 | 17 | 0.6.1 (2018-08-02) 18 | ------------------ 19 | 20 | 0.6.0 (2018-04-12) 21 | ------------------ 22 | 23 | 0.5.4 (2018-04-12) 24 | ------------------ 25 | 26 | 0.5.3 (2016-06-01) 27 | ------------------ 28 | 29 | 0.5.2 (2016-02-10) 30 | ------------------ 31 | 32 | 0.5.1 (2015-02-02) 33 | ------------------ 34 | 35 | 0.5.0 (2015-01-20) 36 | ------------------ 37 | 38 | 0.4.2 (2015-01-14) 39 | ------------------ 40 | 41 | 0.4.1 (2015-01-07) 42 | ------------------ 43 | 44 | 0.4.0 (2014-12-12) 45 | ------------------ 46 | * Add hardware string to Status message. 47 | * Contributors: Mike Purvis 48 | 49 | 0.3.0 (2014-09-10) 50 | ------------------ 51 | 52 | 0.2.1 (2014-09-10) 53 | ------------------ 54 | 55 | 0.2.0 (2014-09-09) 56 | ------------------ 57 | 58 | 0.1.1 (2014-09-06) 59 | ------------------ 60 | 61 | 0.1.0 (2014-09-05) 62 | ------------------ 63 | * New jackal_msgs package. 64 | * Contributors: Mike Purvis 65 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(jackal_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | std_msgs 6 | message_generation 7 | ) 8 | 9 | add_message_files( 10 | FILES 11 | Drive.msg 12 | DriveFeedback.msg 13 | Feedback.msg 14 | Status.msg 15 | ) 16 | 17 | generate_messages( 18 | DEPENDENCIES 19 | std_msgs 20 | ) 21 | 22 | catkin_package(CATKIN_DEPENDS std_msgs message_runtime) 23 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_msgs/msg/Drive.msg: -------------------------------------------------------------------------------- 1 | # This message represents a low-level motor command to Jackal. 2 | 3 | # Command units dependent on the value of this field 4 | int8 MODE_VELOCITY=0 # velocity command (rad/s of wheels) 5 | int8 MODE_PWM=1 # proportion of full voltage command [-1.0..1.0] 6 | int8 MODE_EFFORT=2 # torque command (Nm) 7 | int8 MODE_NONE=-1 # no control, commanded values ignored. 8 | int8 mode 9 | 10 | # Units as above, +ve direction propels chassis forward. 11 | int8 LEFT=0 12 | int8 RIGHT=1 13 | float32[2] drivers 14 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_msgs/msg/DriveFeedback.msg: -------------------------------------------------------------------------------- 1 | # This message represents feedback data from a single drive unit (driver + motor). 2 | 3 | # Current flowing from battery into the MOSFET bridge. 4 | float32 current 5 | 6 | # Instantaneous duty cycle of MOSFET bridge. 7 | float32 duty_cycle 8 | 9 | # Temperatures measured in the MOSFET bridge and on the motor casing, in deg C. 10 | float32 bridge_temperature 11 | float32 motor_temperature 12 | 13 | # Encoder data 14 | float32 measured_velocity # rad/s 15 | float32 measured_travel # rad 16 | 17 | # True if the underlying driver chip reports a fault condition. 18 | bool driver_fault 19 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_msgs/msg/Feedback.msg: -------------------------------------------------------------------------------- 1 | # This message represents high-frequency feedback from the MCU, 2 | # as necessary to support closed-loop control and thermal monitoring. 3 | # Default publish frequency is 50Hz. 4 | 5 | Header header 6 | 7 | DriveFeedback[2] drivers 8 | 9 | # Temperatures 10 | float32 pcb_temperature 11 | float32 mcu_temperature 12 | 13 | # Commanded control mode, use the TYPE_ constants from jackal_msgs/Drive. 14 | int8 commanded_mode 15 | 16 | # Actual control mode. This may differ from the commanded in cases where 17 | # the motor enable is off, the motors are in over-current, etc. 18 | int8 actual_mode 19 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_msgs/msg/Status.msg: -------------------------------------------------------------------------------- 1 | # This message represents Jackal's lower-frequency status updates 2 | # Default publish frequency is 1Hz. 3 | 4 | Header header 5 | 6 | # Commit of firmware source. 7 | string hardware_id 8 | 9 | # Times since MCU power-on and MCU rosserial connection, respectively. 10 | duration mcu_uptime 11 | duration connection_uptime 12 | 13 | # Monitoring the run/stop loop. Changes in these values trigger an immediate 14 | # publish, outside the ordinarily-scheduled 1Hz updates. 15 | bool drivers_active 16 | bool driver_external_stop_present 17 | bool driver_external_stop_stopped 18 | 19 | # Voltage rails, in volts 20 | # Averaged over the message period 21 | float32 measured_battery 22 | float32 measured_12v 23 | float32 measured_5v 24 | 25 | # Current senses available on platform, in amps. 26 | # Averaged over the message period 27 | float32 drive_current 28 | float32 user_current 29 | float32 computer_current 30 | float32 total_current 31 | 32 | # Highest total system current peak as measured in a 1ms window. 33 | float32 total_current_peak 34 | 35 | # Integration of all power consumption since MCU power-on, in watt-hours. 36 | float64 total_power_consumed 37 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | jackal_msgs 4 | 0.6.5 5 | Messages exclusive to Jackal, especially for representing low-level motor commands and sensors. 6 | Mike Purvis 7 | 8 | BSD 9 | 10 | http://wiki.ros.org/jackal_msgs 11 | Mike Purvis 12 | 13 | catkin 14 | message_generation 15 | std_msgs 16 | message_runtime 17 | std_msgs 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_simulator/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package jackal_simulator 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.0 (2015-01-20) 6 | ------------------ 7 | 8 | 0.2.3 (2014-12-12) 9 | ------------------ 10 | 11 | 0.2.2 (2014-09-10) 12 | ------------------ 13 | * Add author tags. 14 | * Contributors: Mike Purvis 15 | 16 | 0.2.1 (2014-09-10) 17 | ------------------ 18 | 19 | 0.2.0 (2014-09-09) 20 | ------------------ 21 | 22 | 0.1.0 (2014-09-07) 23 | ------------------ 24 | * Initial version 25 | * Contributors: Mike Purvis 26 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_simulator/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(jackal_simulator) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /3rdparty/jackal/jackal_simulator/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | jackal_simulator 4 | 0.3.0 5 | Packages for simulating Jackal. 6 | 7 | Mike Purvis 8 | Mike Purvis 9 | 10 | BSD 11 | 12 | http://wiki.ros.org/jackal_simulator 13 | 14 | catkin 15 | jackal_gazebo 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Change log for nmea_msgs package 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.1.0 (2017-12-07) 6 | ------------------ 7 | * Add specific NMEA messages (`#5 `_) 8 | Add messages for the following NMEA sentences: 9 | - GPGGA 10 | - GPGSA 11 | - GPGSV (and a submessage GpgsvSatellite) 12 | - GPRMC 13 | These messages are useful to GPS drivers that parse NMEA sentences 14 | into specific ROS messages. 15 | * Update maintainer to Ed Venator 16 | * Contributors: Edward Venator, Eric Perko 17 | 18 | 1.0.0 (2015-04-23) 19 | ------------------ 20 | * Release into Jade. 21 | 22 | 0.1.1 (2015-02-15) 23 | ------------------ 24 | * Cleanup CMakeLists.txt and package.xml 25 | 26 | 0.1.0 (2013-07-21) 27 | ------------------ 28 | * Initial version (released into Hydro) 29 | * Supports NMEA0183 sentences 30 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(nmea_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS std_msgs message_generation) 5 | 6 | add_message_files( 7 | FILES 8 | Gpgga.msg 9 | Gpgsa.msg 10 | Gpgsv.msg 11 | GpgsvSatellite.msg 12 | Gprmc.msg 13 | Gpgst.msg 14 | Sentence.msg 15 | ) 16 | 17 | generate_messages( 18 | DEPENDENCIES 19 | std_msgs 20 | ) 21 | 22 | catkin_package(CATKIN_DEPENDS std_msgs message_runtime) 23 | 24 | install(FILES LICENSE.txt 25 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 26 | ) 27 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/LICENSE.txt: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2013-2021, ROS Device Driver Contributors 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/README.rst: -------------------------------------------------------------------------------- 1 | nmea_msgs 2 | ========= 3 | 4 | This package contains message definitions for working with NMEA data. 5 | 6 | Please see the ROS Wiki: http://wiki.ros.org/nmea_msgs 7 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/msg/Gpgga.msg: -------------------------------------------------------------------------------- 1 | # Message from GPGGA NMEA String 2 | Header header 3 | 4 | string message_id 5 | 6 | # UTC seconds from midnight 7 | float64 utc_seconds 8 | 9 | float64 lat 10 | float64 lon 11 | 12 | string lat_dir 13 | string lon_dir 14 | 15 | uint32 gps_qual 16 | 17 | uint32 num_sats 18 | float32 hdop 19 | float32 alt 20 | string altitude_units 21 | 22 | float32 undulation 23 | string undulation_units 24 | uint32 diff_age 25 | string station_id 26 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/msg/Gpgsa.msg: -------------------------------------------------------------------------------- 1 | # Message from GPGSA NMEA String 2 | Header header 3 | 4 | string message_id 5 | 6 | string auto_manual_mode 7 | uint8 fix_mode 8 | 9 | uint8[] sv_ids 10 | 11 | float32 pdop 12 | float32 hdop 13 | float32 vdop 14 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/msg/Gpgst.msg: -------------------------------------------------------------------------------- 1 | # Message from GPGST NMEA String 2 | Header header 3 | 4 | string message_id 5 | 6 | # UTC seconds from midnight 7 | float64 utc_seconds 8 | 9 | # Root-Mean-Squared value of standard deviation of range inputs 10 | float32 rms 11 | 12 | # Standard Deviations of semi-major and minor axes of error ellipse 13 | float32 semi_major_dev 14 | float32 semi_minor_dev 15 | 16 | # Orientation of the semi-major axis of error ellipse with respect to true north 17 | float32 orientation 18 | 19 | # Standard Deviations of latitude, longitude, and altitude measurements 20 | float32 lat_dev 21 | float32 lon_dev 22 | float32 alt_dev 23 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/msg/Gpgsv.msg: -------------------------------------------------------------------------------- 1 | # Total number of satellites in view and data about satellites 2 | # Because the NMEA sentence is limited to 4 satellites per message, several 3 | # of these messages may need to be synthesized to get data about all visible 4 | # satellites. 5 | 6 | Header header 7 | 8 | string message_id 9 | 10 | # Number of messages in this sequence 11 | uint8 n_msgs 12 | # This messages number in its sequence. The first message is number 1. 13 | uint8 msg_number 14 | 15 | # Number of satellites currently visible 16 | uint8 n_satellites 17 | 18 | # Up to 4 satellites are described in each message 19 | GpgsvSatellite[] satellites 20 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/msg/GpgsvSatellite.msg: -------------------------------------------------------------------------------- 1 | # Satellite data structure used in GPGSV messages 2 | 3 | # PRN number of the satellite 4 | # GPS = 1..32 5 | # SBAS = 33..64 6 | # GLO = 65..96 7 | uint8 prn 8 | 9 | # Elevation, degrees. Maximum 90 10 | uint8 elevation 11 | 12 | # Azimuth, True North degrees. [0, 359] 13 | uint16 azimuth 14 | 15 | # Signal to noise ratio, 0-99 dB. -1 when null in NMEA sentence (not tracking) 16 | int8 snr 17 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/msg/Gprmc.msg: -------------------------------------------------------------------------------- 1 | # Message from GPRMC NMEA String 2 | Header header 3 | 4 | string message_id 5 | 6 | float64 utc_seconds 7 | string position_status 8 | 9 | float64 lat 10 | float64 lon 11 | 12 | string lat_dir 13 | string lon_dir 14 | 15 | float32 speed 16 | float32 track 17 | string date 18 | float32 mag_var 19 | string mag_var_direction 20 | string mode_indicator 21 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/msg/Sentence.msg: -------------------------------------------------------------------------------- 1 | # A message representing a single NMEA0183 sentence. 2 | 3 | # header.stamp is the ROS Time when the sentence was read. 4 | # header.frame_id is the frame of reference reported by the satellite 5 | # receiver, usually the location of the antenna. This is a 6 | # Euclidean frame relative to the vehicle, not a reference 7 | # ellipsoid. 8 | Header header 9 | 10 | # This should only contain ASCII characters in order to be a valid NMEA0183 sentence. 11 | string sentence 12 | -------------------------------------------------------------------------------- /3rdparty/nmea_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | nmea_msgs 4 | 1.1.0 5 | The nmea_msgs package contains messages related to data in the NMEA format. 6 | Ed Venator 7 | BSD-3-Clause 8 | http://ros.org/wiki/nmea_msgs 9 | Eric Perko 10 | 11 | catkin 12 | std_msgs 13 | message_generation 14 | std_msgs 15 | message_runtime 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /3rdparty/rosserial/.travis.yml: -------------------------------------------------------------------------------- 1 | # This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git). 2 | # For troubleshooting, see readme (https://github.com/ros-industrial/industrial_ci/blob/master/README.rst) 3 | 4 | language: generic 5 | 6 | services: 7 | - docker 8 | 9 | cache: 10 | directories: 11 | - $HOME/.ccache 12 | 13 | git: 14 | quiet: true 15 | 16 | env: 17 | global: 18 | - ROS_REPO=ros 19 | - CCACHE_DIR=$HOME/.ccache 20 | matrix: 21 | - ROS_DISTRO="noetic" ROS_REPO=ros-shadow-fixed 22 | 23 | install: 24 | - git clone --quiet --depth 1 https://github.com/ros-industrial/industrial_ci.git .industrial_ci -b master 25 | script: 26 | - .industrial_ci/travis.sh 27 | -------------------------------------------------------------------------------- /3rdparty/rosserial/README.md: -------------------------------------------------------------------------------- 1 | # rosserial 2 | 3 | [![Build Status](https://travis-ci.org/ros-drivers/rosserial.svg?branch=melodic-devel)](https://travis-ci.org/ros-drivers/rosserial) 4 | 5 | Please see [rosserial on the ROS wiki](http://wiki.ros.org/rosserial) to get started. 6 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.7.2) 2 | project(rosserial_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | message_generation 6 | ) 7 | 8 | add_message_files(FILES 9 | Log.msg 10 | TopicInfo.msg 11 | ) 12 | 13 | add_service_files(FILES 14 | RequestParam.srv 15 | ) 16 | 17 | generate_messages() 18 | 19 | catkin_package(CATKIN_DEPENDS 20 | message_runtime 21 | ) 22 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_msgs/msg/Log.msg: -------------------------------------------------------------------------------- 1 | 2 | #ROS Logging Levels 3 | uint8 ROSDEBUG=0 4 | uint8 INFO=1 5 | uint8 WARN=2 6 | uint8 ERROR=3 7 | uint8 FATAL=4 8 | 9 | uint8 level 10 | string msg 11 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_msgs/msg/TopicInfo.msg: -------------------------------------------------------------------------------- 1 | # special topic_ids 2 | uint16 ID_PUBLISHER=0 3 | uint16 ID_SUBSCRIBER=1 4 | uint16 ID_SERVICE_SERVER=2 5 | uint16 ID_SERVICE_CLIENT=4 6 | uint16 ID_PARAMETER_REQUEST=6 7 | uint16 ID_LOG=7 8 | uint16 ID_TIME=10 9 | uint16 ID_TX_STOP=11 10 | 11 | # The endpoint ID for this topic 12 | uint16 topic_id 13 | 14 | string topic_name 15 | string message_type 16 | 17 | # MD5 checksum for this message type 18 | string md5sum 19 | 20 | # size of the buffer message must fit in 21 | int32 buffer_size 22 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | rosserial_msgs 3 | 0.9.2 4 | 5 | Messages for automatic topic configuration using rosserial. 6 | 7 | Michael Ferguson 8 | Paul Bouchier 9 | Mike Purvis 10 | BSD 11 | http://ros.org/wiki/rosserial_msgs 12 | 13 | catkin 14 | 15 | message_generation 16 | 17 | message_runtime 18 | 19 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_msgs/srv/RequestParam.srv: -------------------------------------------------------------------------------- 1 | string name 2 | 3 | --- 4 | 5 | int32[] ints 6 | float32[] floats 7 | string[] strings 8 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_server/include/rosserial_server/msg_lookup.h: -------------------------------------------------------------------------------- 1 | /** 2 | * \author Mike Purvis 3 | * \copyright Copyright (c) 2019, Clearpath Robotics, Inc. 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 Clearpath Robotics, Inc. nor the 13 | * names of its contributors may be used to endorse or promote products 14 | * derived from this software without specific prior written permission. 15 | * 16 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 17 | * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 18 | * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 19 | * DISCLAIMED. IN NO EVENT SHALL CLEARPATH ROBOTICS, INC. BE LIABLE FOR ANY 20 | * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 21 | * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 22 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 23 | * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 24 | * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | * 27 | * Please send comments, questions, or patches to code@clearpathrobotics.com 28 | */ 29 | 30 | #include 31 | #include 32 | 33 | namespace rosserial_server 34 | { 35 | 36 | struct MsgInfo 37 | { 38 | std::string md5sum; 39 | std::string full_text; 40 | }; 41 | 42 | const MsgInfo lookupMessage(const std::string& message_type, const std::string submodule = "msg"); 43 | 44 | } // namespace rosserial_server 45 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_server/launch/serial.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_server/launch/socket.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_server/launch/udp_socket.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /3rdparty/rosserial/rosserial_server/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | rosserial_server 4 | 0.9.2 5 | 6 | A more performance- and stability-oriented server alternative implemented 7 | in C++ to rosserial_python. 8 | 9 | 10 | Mike Purvis 11 | Mike Purvis 12 | 13 | BSD 14 | 15 | catkin 16 | rosserial_msgs 17 | std_msgs 18 | roscpp 19 | topic_tools 20 | python3-dev 21 | libboost-thread-dev 22 | libboost-thread 23 | 24 | -------------------------------------------------------------------------------- /3rdparty/ufomap/LICENSE: -------------------------------------------------------------------------------- 1 | BSD 2-Clause License 2 | 3 | Copyright (c) 2020, UFO 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 17 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 18 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 19 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 20 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 21 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 22 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 23 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 24 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 25 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap/README.md: -------------------------------------------------------------------------------- 1 | # UFOMap: An Efficient Probabilistic 3D Mapping Framework That Embraces the Unknown 2 | 3 | UFOMap is an effienct probabilistic 3D mapping framework with an explicit representation of unknown space. 4 | 5 | ## Table of Contents 6 | Please see the [Wiki](https://github.com/UnknownFreeOccupied/ufomap/wiki) for how to install and use UFOMap. 7 | 1. [Setup](https://github.com/UnknownFreeOccupied/ufomap/wiki/Tutorials) 8 | 2. [Tutorials](https://github.com/UnknownFreeOccupied/ufomap/wiki/Setup) 9 | 3. [ROS Tutorials](https://github.com/UnknownFreeOccupied/ufomap/wiki/ROS-Tutorials) 10 | 4. [Advanced ROS Tutorials](https://github.com/UnknownFreeOccupied/ufomap/wiki/Advanced-ROS-Tutorials) 11 | 5. [Performance](https://github.com/UnknownFreeOccupied/ufomap/wiki/Performance) 12 | 6. [Example Outputs](https://github.com/UnknownFreeOccupied/ufomap/wiki/Example-Outputs) 13 | 7. [Data Repository](https://github.com/UnknownFreeOccupied/ufomap/wiki/Data-Repository) 14 | 8. [API](https://github.com/UnknownFreeOccupied/ufomap/wiki/API) 15 | 16 | ## Credits 17 | ### Paper 18 | * [IEEE](https://ieeexplore.ieee.org/abstract/document/9158399) 19 | * [ArXiv](https://arxiv.org/abs/2003.04749) 20 | ### Cite 21 | If you use UFOMap in a scientific publication, please cite the following paper: 22 | * Daniel Duberg and Patric Jensfelt, "UFOMap: An Efficient Probabilistic 3D Mapping Framework That Embraces the Unknown," in IEEE Robotics and Automation Letters, vol. 5, no. 4, pp. 6411-6418, Oct. 2020, doi: 10.1109/LRA.2020.3013861. 23 | ```latex 24 | @article{duberg2020ufomap, 25 | author={Daniel Duberg and Patric Jensfelt}, 26 | journal={IEEE Robotics and Automation Letters}, 27 | title={{UFOMap}: An Efficient Probabilistic {3D} Mapping Framework That Embraces the Unknown}, 28 | year={2020}, 29 | volume={5}, 30 | number={4}, 31 | pages={6411-6418}, 32 | doi={10.1109/LRA.2020.3013861} 33 | } 34 | ``` 35 | ### Videos 36 | * [YouTube Playlist](https://youtube.com/playlist?list=PLoZnKRp2UVom4bv2fUVXgI5VCbuTrfrU3) 37 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap/cmake/ufomapConfig.cmake.in: -------------------------------------------------------------------------------- 1 | @PACKAGE_INIT@ 2 | 3 | include("${CMAKE_CURRENT_LIST_DIR}/ufomapTargets.cmake") 4 | check_required_components("ufomap") -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap/docs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/ufomap/ufomap/docs/CMakeLists.txt -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap/include/ufo/geometry/cone.h: -------------------------------------------------------------------------------- 1 | /** 2 | * UFOGeometry - the geometry library used in UFO 3 | * 4 | * @author D. Duberg, KTH Royal Institute of Technology, Copyright (c) 2020. 5 | * @see https://github.com/UnknownFreeOccupied/ufogeometry 6 | * License: BSD 3 7 | * 8 | */ 9 | 10 | /* 11 | * BSD 3-Clause License 12 | * 13 | * Copyright (c) 2020, D. Duberg, KTH Royal Institute of Technology 14 | * All rights reserved. 15 | * 16 | * Redistribution and use in source and binary forms, with or without 17 | * modification, are permitted provided that the following conditions are met: 18 | * 19 | * 1. Redistributions of source code must retain the above copyright notice, this 20 | * list of conditions and the following disclaimer. 21 | * 22 | * 2. Redistributions in binary form must reproduce the above copyright notice, 23 | * this list of conditions and the following disclaimer in the documentation 24 | * and/or other materials provided with the distribution. 25 | * 26 | * 3. Neither the name of the copyright holder nor the names of its 27 | * contributors may be used to endorse or promote products derived from 28 | * this software without specific prior written permission. 29 | * 30 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 31 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 32 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 33 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 34 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 35 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 36 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 37 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 38 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 39 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 40 | */ 41 | 42 | #ifndef UFO_GEOMETRY_CONE_H 43 | #define UFO_GEOMETRY_CONE_H 44 | 45 | #include 46 | 47 | namespace ufo::geometry { 48 | struct Cone { 49 | }; 50 | } // namespace ufo::geometry 51 | 52 | #endif // UFO_GEOMETRY_CONE_H 53 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap/include/ufo/geometry/point.h: -------------------------------------------------------------------------------- 1 | /** 2 | * UFOGeometry - the geometry library used in UFO 3 | * 4 | * @author D. Duberg, KTH Royal Institute of Technology, Copyright (c) 2020. 5 | * @see https://github.com/UnknownFreeOccupied/ufogeometry 6 | * License: BSD 3 7 | * 8 | */ 9 | 10 | /* 11 | * BSD 3-Clause License 12 | * 13 | * Copyright (c) 2020, D. Duberg, KTH Royal Institute of Technology 14 | * All rights reserved. 15 | * 16 | * Redistribution and use in source and binary forms, with or without 17 | * modification, are permitted provided that the following conditions are met: 18 | * 19 | * 1. Redistributions of source code must retain the above copyright notice, this 20 | * list of conditions and the following disclaimer. 21 | * 22 | * 2. Redistributions in binary form must reproduce the above copyright notice, 23 | * this list of conditions and the following disclaimer in the documentation 24 | * and/or other materials provided with the distribution. 25 | * 26 | * 3. Neither the name of the copyright holder nor the names of its 27 | * contributors may be used to endorse or promote products derived from 28 | * this software without specific prior written permission. 29 | * 30 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 31 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 32 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 33 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 34 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 35 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 36 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 37 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 38 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 39 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 40 | */ 41 | 42 | #ifndef UFO_GEOMETRY_POINT_H 43 | #define UFO_GEOMETRY_POINT_H 44 | 45 | #include 46 | 47 | namespace ufo::geometry { 48 | using Point = math::Vector3; 49 | } // namespace ufo::geometry 50 | 51 | #endif // UFO_GEOMETRY_POINT_H -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap/include/ufo/map/ufomap.h: -------------------------------------------------------------------------------- 1 | /** 2 | * UFOMap: An Efficient Probabilistic 3D Mapping Framework That Embraces the Unknown 3 | * 4 | * @author D. Duberg, KTH Royal Institute of Technology, Copyright (c) 2020. 5 | * @see https://github.com/UnknownFreeOccupied/ufomap 6 | * License: BSD 3 7 | * 8 | */ 9 | 10 | /* 11 | * BSD 3-Clause License 12 | * 13 | * Copyright (c) 2020, D. Duberg, KTH Royal Institute of Technology 14 | * All rights reserved. 15 | * 16 | * Redistribution and use in source and binary forms, with or without 17 | * modification, are permitted provided that the following conditions are met: 18 | * 19 | * 1. Redistributions of source code must retain the above copyright notice, this 20 | * list of conditions and the following disclaimer. 21 | * 22 | * 2. Redistributions in binary form must reproduce the above copyright notice, 23 | * this list of conditions and the following disclaimer in the documentation 24 | * and/or other materials provided with the distribution. 25 | * 26 | * 3. Neither the name of the copyright holder nor the names of its 27 | * contributors may be used to endorse or promote products derived from 28 | * this software without specific prior written permission. 29 | * 30 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 31 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 32 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 33 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 34 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 35 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 36 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 37 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 38 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 39 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 40 | */ 41 | 42 | #ifndef UFO_MAP_UFO_MAP_H 43 | #define UFO_MAP_UFO_MAP_H 44 | 45 | #include 46 | #include 47 | #include 48 | #include 49 | 50 | #endif // UFO_MAP_UFO_MAP_H -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ufomap 4 | 1.0.0 5 | The ufomap package 6 | 7 | Daniel Duberg 8 | Daniel Duberg 9 | 10 | BSD 11 | 12 | https://github.com/danielduberg/ufomap 13 | 14 | 15 | catkin 16 | lz4 17 | tbb 18 | 19 | doxygen 20 | 21 | 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap/tests/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/ufomap/ufomap/tests/CMakeLists.txt -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/README.md: -------------------------------------------------------------------------------- 1 | # ufomap_ros 2 | ufomap_ros is a ROS interface for UFOMap 3 | 4 | ## Table of Contents 5 | * [ufomap_mapping](https://github.com/UnknownFreeOccupied/ufomap/tree/master/ufomap_ros/ufomap_mapping) 6 | * Default UFOMap mapping server. Use this if you want to quickly get started mapping! 7 | * [ufomap_msgs](https://github.com/UnknownFreeOccupied/ufomap/tree/master/ufomap_ros/ufomap_msgs) 8 | * Contains UFOMap ROS messages and functions to convert between message and UFOMap types. 9 | * [ufomap_ros](https://github.com/UnknownFreeOccupied/ufomap/tree/master/ufomap_ros/ufomap_ros) 10 | * Contains functions to convert between ROS and UFOMap types. 11 | * [ufomap_rviz_plugins](https://github.com/UnknownFreeOccupied/ufomap/tree/master/ufomap_ros/ufomap_rviz_plugins) 12 | * Contains RViz plugins to visualize UFOMap in RViz. 13 | * [ufomap_srvs](https://github.com/UnknownFreeOccupied/ufomap/tree/master/ufomap_ros/ufomap_srvs) 14 | * Contains UFOMap ROS services. 15 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_manager/msg/CellCode.msg: -------------------------------------------------------------------------------- 1 | uint32 depth 2 | uint64 Code 3 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_manager/msg/UfomapWithFrontiers.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | ufomap_msgs/UFOMap ufomap 4 | 5 | #geometry_msgs/Point[] local_frontiers_center 6 | #geometry_msgs/Point[] global_frontiers_center 7 | # 8 | #int32 frontiers_depth 9 | 10 | ufomap_manager/CellCode[] local_frontiers 11 | ufomap_manager/CellCode[] global_frontiers 12 | ufomap_manager/CellCode[] changed_cell_codes 13 | ufomap_manager/CellCode[] known_cell_codes 14 | 15 | # 构建ufomap时机器人的参数配置 16 | string frame_id 17 | string robot_base_frame_id 18 | float64 robot_height 19 | float64 robot_bottom 20 | float64 robot_radius 21 | float64 max_range 22 | 23 | uint32 known_plane_cell_num -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_manager/src/frontier_manager_node.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2020/6/19. 3 | // 4 | #include 5 | #include 6 | 7 | int main(int argc, char** argv) 8 | { 9 | ros::init(argc, argv, "frontier_manager"); 10 | ros::NodeHandle nh; 11 | ros::NodeHandle nh_private("~"); 12 | ufomap_manager::FrontierManager frontier(nh,nh_private); 13 | 14 | ros::spin(); 15 | return 0; 16 | } 17 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_manager/src/read_trajectory.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/9/1. 3 | // 4 | 5 | 6 | #include 7 | #include 8 | 9 | #include 10 | #include 11 | #include 12 | 13 | using namespace std; 14 | 15 | int main(int argc, char** argv){ 16 | 17 | ros::init(argc, argv, "read_trajectory"); 18 | ros::NodeHandle nh; 19 | ros::NodeHandle nh_private("~"); 20 | 21 | ros::Publisher pub = nh_private.advertise("trajectory_odom", 1); 22 | ros::Publisher pub_point = nh_private.advertise("trajectory_points",1); 23 | 24 | std::string ns = ros::this_node::getName(); 25 | std::string txt_name = "tracjectory.txt"; 26 | if (!ros::param::get(ns + "/txt_name", txt_name)) { 27 | ROS_WARN( 28 | "No txt_name specified. Looking for %s. Default is 'tracjectory.txt'.", 29 | (ns + "/txt_name").c_str()); 30 | } 31 | 32 | nav_msgs::Odometry robot_odom; 33 | sensor_msgs::PointCloud2 point_cloud; 34 | robot_odom.header.frame_id = "world"; 35 | point_cloud.header.frame_id = "world"; 36 | 37 | string line; 38 | ifstream fin; 39 | fin.open(txt_name,ios::in); 40 | if(!fin.is_open()){ 41 | std::cout<<"file open failed"< 5 | #include 6 | 7 | 8 | int main(int argc, char** argv) 9 | { 10 | ros::init(argc, argv, "ufomap_manager"); 11 | ros::NodeHandle nh; 12 | ros::NodeHandle nh_private("~"); 13 | ufomap_manager::UFOMapManager manager(nh,nh_private); 14 | 15 | ros::spin(); 16 | return 0; 17 | } -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_mapping/launch/server.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_mapping/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ufomap_mapping 4 | 1.0.0 5 | The ufomap_mapping package 6 | 7 | Daniel Duberg 8 | 9 | BSD 10 | 11 | https://github.com/danielduberg/UFOMap 12 | 13 | Daniel Duberg 14 | 15 | catkin 16 | diagnostic_msgs 17 | dynamic_reconfigure 18 | geometry_msgs 19 | roscpp 20 | sensor_msgs 21 | std_msgs 22 | std_srvs 23 | tf2 24 | tf2_ros 25 | tf2_sensor_msgs 26 | ufomap_msgs 27 | ufomap_ros 28 | ufomap_srvs 29 | 30 | ufomap 31 | 32 | doxygen 33 | 34 | 35 | 36 | 37 | 38 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.8.2) 2 | project(ufomap_msgs) 3 | 4 | set(CMAKE_CXX_STANDARD 17) 5 | 6 | find_package(catkin REQUIRED COMPONENTS 7 | geometry_msgs 8 | message_generation 9 | std_msgs 10 | ) 11 | 12 | find_package(ufomap REQUIRED) 13 | 14 | add_message_files( 15 | DIRECTORY msg 16 | FILES 17 | AABB.msg 18 | BoundingVolume.msg 19 | # Capsule.msg 20 | # Cone.msg 21 | # Cylinder.msg 22 | # Ellipsoid.msg 23 | Frustum.msg 24 | LineSegment.msg 25 | OBB.msg 26 | Plane.msg 27 | Point.msg 28 | Ray.msg 29 | Sphere.msg 30 | # Triangle.msg 31 | UFOMap.msg 32 | UFOMapMetaData.msg 33 | UFOMapStamped.msg 34 | ) 35 | 36 | generate_messages( 37 | DEPENDENCIES 38 | geometry_msgs 39 | std_msgs 40 | ) 41 | 42 | catkin_package( 43 | INCLUDE_DIRS include 44 | LIBRARIES ${PROJECT_NAME} ${catkin_LIBRARIES} 45 | CATKIN_DEPENDS geometry_msgs message_runtime std_msgs 46 | ) 47 | 48 | include_directories( 49 | include 50 | ${catkin_INCLUDE_DIRS} 51 | ) 52 | 53 | add_library(${PROJECT_NAME} STATIC src/conversions.cpp) 54 | add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) 55 | target_link_libraries(${PROJECT_NAME} 56 | PUBLIC 57 | ${catkin_LIBRARIES} 58 | UFO::Map 59 | ) 60 | 61 | install(TARGETS ${PROJECT_NAME} 62 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 63 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 64 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 65 | ) 66 | 67 | install(DIRECTORY include/${PROJECT_NAME}/ 68 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 69 | FILES_MATCHING PATTERN "*.h" 70 | ) -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/AABB.msg: -------------------------------------------------------------------------------- 1 | ufomap_msgs/Point center 2 | 3 | ufomap_msgs/Point half_size -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/BoundingVolume.msg: -------------------------------------------------------------------------------- 1 | ufomap_msgs/AABB[] aabbs 2 | 3 | # ufomap_msgs/Capsule[] capsules 4 | 5 | # ufomap_msgs/Cone[] cones 6 | 7 | # ufomap_msgs/Cylinder[] cylinders 8 | 9 | # ufomap_msgs/Ellipsoid[] ellipsoids 10 | 11 | ufomap_msgs/Frustum[] frustums 12 | 13 | ufomap_msgs/LineSegment[] line_segments 14 | 15 | ufomap_msgs/OBB[] obbs 16 | 17 | ufomap_msgs/Plane[] planes 18 | 19 | ufomap_msgs/Point[] points 20 | 21 | ufomap_msgs/Ray[] rays 22 | 23 | ufomap_msgs/Sphere[] spheres 24 | 25 | # ufomap_msgs/Triangle[] triangles -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Capsule.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Capsule.msg -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Cone.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Cone.msg -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Cylinder.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Cylinder.msg -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Ellipsoid.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Ellipsoid.msg -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Frustum.msg: -------------------------------------------------------------------------------- 1 | ufomap_msgs/Plane[6] planes -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/LineSegment.msg: -------------------------------------------------------------------------------- 1 | ufomap_msgs/Point start 2 | 3 | ufomap_msgs/Point end -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/OBB.msg: -------------------------------------------------------------------------------- 1 | ufomap_msgs/Point center 2 | 3 | ufomap_msgs/Point half_size 4 | 5 | ufomap_msgs/Point rotation -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Plane.msg: -------------------------------------------------------------------------------- 1 | ufomap_msgs/Point normal 2 | 3 | float64 distance -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Point.msg: -------------------------------------------------------------------------------- 1 | float64 x 2 | float64 y 3 | float64 z -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Ray.msg: -------------------------------------------------------------------------------- 1 | ufomap_msgs/Point origin 2 | 3 | ufomap_msgs/Point direction -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Sphere.msg: -------------------------------------------------------------------------------- 1 | ufomap_msgs/Point center 2 | 3 | float64 radius -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Triangle.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/Triangle.msg -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/UFOMap.msg: -------------------------------------------------------------------------------- 1 | # A 3D map in binary format, as Octree 2 | ufomap_msgs/UFOMapMetaData info 3 | 4 | # Binary serialization of Octree, use conversions.h to read and write octrees 5 | int8[] data -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/UFOMapMetaData.msg: -------------------------------------------------------------------------------- 1 | # File version used 2 | string version 3 | 4 | # Class id of the contained Octree 5 | string id 6 | 7 | # Resolution (in m) of the octree leaf nodes 8 | float64 resolution 9 | 10 | # Number of depth levels 11 | uint8 depth_levels 12 | 13 | # If data is compressed 14 | bool compressed 15 | 16 | # Size of data uncompressed 17 | int32 uncompressed_data_size 18 | 19 | # Bounding volume 20 | ufomap_msgs/BoundingVolume bounding_volume -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/msg/UFOMapStamped.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | ufomap_msgs/UFOMap map -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ufomap_msgs 4 | 1.0.0 5 | The ufomap_msgs package provides messages and serializations for the UFOMap library 6 | 7 | Daniel Duberg 8 | Daniel Duberg 9 | 10 | BSD 11 | 12 | https://github.com/danielduberg/ufo_ros 13 | 14 | catkin 15 | geometry_msgs 16 | std_msgs 17 | 18 | message_generation 19 | message_runtime 20 | 21 | ufomap 22 | 23 | doxygen 24 | 25 | 26 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_ros/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.8.2) 2 | project(ufomap_ros) 3 | 4 | set(CMAKE_CXX_STANDARD 17) 5 | 6 | find_package(catkin REQUIRED COMPONENTS 7 | geometry_msgs 8 | roscpp 9 | sensor_msgs 10 | ) 11 | 12 | find_package(ufomap REQUIRED) 13 | 14 | catkin_package( 15 | INCLUDE_DIRS include ${catkin_INCLUDE_DIRS} 16 | LIBRARIES ${PROJECT_NAME} ${catkin_LIBRARIES} 17 | CATKIN_DEPENDS geometry_msgs roscpp sensor_msgs 18 | ) 19 | 20 | include_directories( 21 | include 22 | ${catkin_INCLUDE_DIRS} 23 | ) 24 | 25 | add_library(${PROJECT_NAME} STATIC 26 | src/conversions.cpp 27 | ) 28 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 29 | target_link_libraries(${PROJECT_NAME} 30 | PUBLIC 31 | ${catkin_LIBRARIES} 32 | UFO::Map 33 | ) 34 | 35 | install(TARGETS ${PROJECT_NAME} 36 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 37 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 38 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 39 | ) 40 | 41 | install(DIRECTORY include/${PROJECT_NAME}/ 42 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 43 | FILES_MATCHING PATTERN "*.h" 44 | # PATTERN ".svn" EXCLUDE 45 | ) -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_ros/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ufomap_ros 4 | 1.0.0 5 | The ufomap_ros package provides conversion functions between UFOMap and ROS native types 6 | 7 | Daniel Duberg 8 | Daniel Duberg 9 | 10 | BSD 11 | 12 | https://github.com/danielduberg/ufomap_ros 13 | 14 | catkin 15 | geometry_msgs 16 | roscpp 17 | sensor_msgs 18 | 19 | ufomap 20 | 21 | doxygen 22 | 23 | 24 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_rviz_plugins/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ufomap_rviz_plugins 4 | 1.0.0 5 | The ufomap_rviz_plugins package 6 | 7 | Daniel Duberg 8 | 9 | BSD 10 | 11 | 12 | 13 | 14 | 15 | 16 | Daniel Duberg 17 | 18 | catkin 19 | roscpp 20 | rviz 21 | ufomap_msgs 22 | ufomap_ros 23 | 24 | qtbase5-dev 25 | libqt5-core 26 | libqt5-widgets 27 | 28 | ufomap 29 | 30 | doxygen 31 | 32 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_rviz_plugins/plugin_description.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Displays a UFOMap. 5 | 6 | ufomap_msgs/UFOMapStamped 7 | 8 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_srvs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(ufomap_srvs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | message_generation 6 | ufomap_msgs 7 | ) 8 | 9 | add_service_files( 10 | FILES 11 | ClearVolume.srv 12 | GetMap.srv 13 | Reset.srv 14 | SaveMap.srv 15 | ) 16 | 17 | generate_messages( 18 | DEPENDENCIES 19 | ufomap_msgs 20 | ) 21 | 22 | catkin_package( 23 | CATKIN_DEPENDS message_runtime ufomap_msgs 24 | ) 25 | 26 | install(DIRECTORY include/${PROJECT_NAME}/ 27 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 28 | FILES_MATCHING PATTERN "*.h" 29 | ) -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_srvs/srv/ClearVolume.srv: -------------------------------------------------------------------------------- 1 | # Clear a part of the map, specified by a bounding volume. 2 | # Sets all voxels inside the bounding volume to ~clamping_thres_min/free space. 3 | 4 | # The bounding volume 5 | ufomap_msgs/BoundingVolume bounding_volume 6 | # The depth at which it should be cleared 7 | uint8 depth 8 | --- 9 | # If it was successful 10 | bool success 11 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_srvs/srv/GetMap.srv: -------------------------------------------------------------------------------- 1 | # Get the complete map at a specified depth 2 | 3 | # The depth of the map to return 4 | uint8 depth 5 | # If the message should be compressed 6 | bool compress 7 | # Bounding volume of which part of the map should be returned 8 | ufomap_msgs/BoundingVolume bounding_volume 9 | --- 10 | # If it was successful 11 | bool success 12 | # The map to be returned 13 | ufomap_msgs/UFOMap map 14 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_srvs/srv/Reset.srv: -------------------------------------------------------------------------------- 1 | # Resets the complete map. 2 | 3 | # The resolution of the new map 4 | float64 new_resolution 5 | # The number of depth levels in the new map 6 | uint8 new_depth_levels 7 | --- 8 | # If it was successful 9 | bool success 10 | -------------------------------------------------------------------------------- /3rdparty/ufomap/ufomap_ros/ufomap_srvs/srv/SaveMap.srv: -------------------------------------------------------------------------------- 1 | # Save the map to file 2 | 3 | # Name of the file 4 | string filename 5 | # The depth of the map to save 6 | uint8 depth 7 | # If the file should be compressed 8 | bool compress 9 | # Compression level (higher number equals more compressed) 10 | int32 compression_level 11 | # Bounding volume of which part of the map should be saved 12 | ufomap_msgs/BoundingVolume bounding_volume 13 | --- 14 | # If it was successful 15 | bool success 16 | -------------------------------------------------------------------------------- /fael_planner/control_planner_interface/action/ExplorerPlanner.action: -------------------------------------------------------------------------------- 1 | 2 | int32 iteration_id 3 | 4 | --- 5 | Path[] paths 6 | 7 | --- 8 | 9 | bool is_get_path -------------------------------------------------------------------------------- /fael_planner/control_planner_interface/action/VehicleExecute.action: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | Path[] paths 3 | --- 4 | bool finish 5 | 6 | --- 7 | geometry_msgs/Pose current_pose 8 | int32 current_waypoint_id -------------------------------------------------------------------------------- /fael_planner/control_planner_interface/include/control_planner_interface/control_planner_interface.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/11/23. 3 | // 4 | 5 | #ifndef TOPO_PLANNER_WS_CONTROL_PLANNER_INTERFACE_H 6 | #define TOPO_PLANNER_WS_CONTROL_PLANNER_INTERFACE_H 7 | 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | #include "control_planner_interface/pci_manager.h" 18 | 19 | #include 20 | #include "control_planner_interface/ExplorerPlannerAction.h" 21 | 22 | namespace interface { 23 | 24 | class ControlPlannerInterface { 25 | 26 | public: 27 | 28 | enum struct RobotMotionState { 29 | waiting = 0, executing = 1, stoping = 2 30 | }; 31 | 32 | typedef actionlib::SimpleActionClient ExplorationPlannerClient; 33 | 34 | ros::NodeHandle nh_; 35 | ros::NodeHandle nh_private_; 36 | 37 | std::shared_ptr pci_manager_; 38 | 39 | ros::Subscriber odometry_sub_; 40 | 41 | ExplorationPlannerClient planner_client_; 42 | 43 | std::string frame_id_; 44 | bool pose_is_ready_; 45 | 46 | double init_x_; 47 | double init_y_; 48 | double init_z_; 49 | 50 | geometry_msgs::Pose current_pose_; 51 | 52 | ControlPlannerInterface(ros::NodeHandle &nh, ros::NodeHandle &nh_private, 53 | std::shared_ptr &pci_manager); 54 | 55 | bool loadParams(); 56 | 57 | bool init(); 58 | 59 | void odometryCallback(const nav_msgs::OdometryConstPtr &odom); 60 | 61 | bool callForPlanner(const int &iteration_id, std::vector &path_segments); 62 | 63 | void executePath(const std::vector &path_segments); 64 | 65 | void goToWayPose(geometry_msgs::Pose &pose); 66 | 67 | bool isGoalReached(); 68 | 69 | void cancelCurrentGoal(); 70 | 71 | void stopMove(); 72 | 73 | }; 74 | } 75 | 76 | 77 | #endif //TOPO_PLANNER_WS_CONTROL_PLANNER_INTERFACE_H 78 | -------------------------------------------------------------------------------- /fael_planner/control_planner_interface/include/control_planner_interface/pci_vehicle.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/11/30. 3 | // 4 | 5 | #ifndef TOPO_PLANNER_WS_PCI_VEHICLE_H 6 | #define TOPO_PLANNER_WS_PCI_VEHICLE_H 7 | 8 | #include "control_planner_interface/pci_manager.h" 9 | 10 | #include 11 | #include 12 | 13 | 14 | 15 | namespace interface { 16 | 17 | class PCIVehicle : public PCIManager { 18 | public: 19 | 20 | typedef actionlib::SimpleActionClient VehicleExecuteActionClient; 21 | 22 | PCIVehicle(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private); 23 | 24 | bool loadParams(const std::string ns) override; 25 | 26 | bool initialize() override; 27 | 28 | void setCurrentPose(const geometry_msgs::Pose &pose) override; 29 | 30 | void setFrameId(const std::string &frame_id) override; 31 | 32 | bool goToWaypoint(const geometry_msgs::Pose &pose) override; 33 | 34 | bool executePath(const std::vector &path_segments, 35 | std::vector &modified_path) override; 36 | 37 | bool isGoalReached() override; 38 | 39 | void cancelCurrentGoal() override; 40 | 41 | void stopMove() override; 42 | 43 | private: 44 | 45 | ros::Subscriber status_sub_; 46 | ros::Publisher robot_status_pub_; 47 | 48 | VehicleExecuteActionClient vehicle_execute_client_; 49 | VehicleExecuteActionClient vehicle_stop_client_; 50 | 51 | std::string frame_id_; 52 | 53 | int n_seq_; 54 | }; 55 | } 56 | 57 | 58 | #endif //TOPO_PLANNER_WS_PCI_VEHICLE_H 59 | -------------------------------------------------------------------------------- /fael_planner/control_planner_interface/msg/Path.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/Pose[] path -------------------------------------------------------------------------------- /fael_planner/control_planner_interface/msg/PlannerMsgs.msg: -------------------------------------------------------------------------------- 1 | 2 | int32 current_iteration_id 3 | int32 current_goal_id 4 | bool is_current_goal_scanned 5 | bool is_exploration_finished -------------------------------------------------------------------------------- /fael_planner/exploration_manager/launch/explorer.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 | -------------------------------------------------------------------------------- /fael_planner/exploration_manager/launch/robot_move.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 | -------------------------------------------------------------------------------- /fael_planner/exploration_manager/launch/sim_env.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /fael_planner/exploration_manager/src/explorer_node.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/12/9. 3 | // 4 | 5 | #include 6 | #include 7 | #include 8 | 9 | int main(int argc, char **argv) { 10 | ros::init(argc, argv, "explorer_node"); 11 | 12 | 13 | ros::NodeHandle nh_private("~"); 14 | ros::NodeHandle nh; 15 | 16 | std::shared_ptr pci_manager = std::make_shared(nh, nh_private); 17 | std::shared_ptr interface = std::make_shared( 18 | nh, nh_private, pci_manager); 19 | 20 | 21 | explorer::Explorer explorer(nh, nh_private, interface); 22 | 23 | return 0; 24 | } 25 | -------------------------------------------------------------------------------- /fael_planner/planner/include/perception/lidar_model.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2022/4/7. 3 | // 4 | 5 | #ifndef ROBO_PLANNER_WS_LIDAR_MODEL_H 6 | #define ROBO_PLANNER_WS_LIDAR_MODEL_H 7 | 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | class LidarModel { 15 | 16 | double max_range_; 17 | int line_num_; 18 | double vertical_angle_theta_; 19 | double vertical_angle_min_; 20 | double vertical_angle_max_; 21 | 22 | int horizontal_point_num_; 23 | double horizontal_angle_theta_; 24 | double horizontal_angle_min_; 25 | double horizontal_angle_max_; 26 | 27 | std::map> lidar_point_cloud_; 28 | 29 | 30 | public: 31 | //Initialize lidar model 32 | LidarModel(double max_range, 33 | double vertical_angle_theta = 2.0, double vertical_angle_min = -15.0, double vertical_angle_max = 15.0, 34 | double horizontal_angle_theta = 0.4, double horizontal_angle_min = 0.0, double horizontal_angle_max = 360.0); 35 | 36 | pcl::PointCloud combineCloud(pcl::PointCloud &input_cloud); 37 | 38 | pcl::PointCloud expandNoRay(pcl::PointCloud &input_cloud); 39 | 40 | }; 41 | 42 | 43 | #endif //ROBO_PLANNER_WS_LIDAR_MODEL_H 44 | -------------------------------------------------------------------------------- /fael_planner/planner/include/perception/map_3d.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2022/1/9. 3 | // 4 | 5 | #ifndef ROBO_PLANNER_WS_MAP_H 6 | #define ROBO_PLANNER_WS_MAP_H 7 | 8 | 9 | #include 10 | 11 | #include "utils/frontier.h" 12 | 13 | namespace perception { 14 | 15 | using namespace utils; 16 | 17 | class Map3D { 18 | public: 19 | typedef std::shared_ptr Ptr; 20 | 21 | Map3D()= default; 22 | 23 | virtual FrontierSet getFrontiers() const = 0; 24 | 25 | virtual bool isFrontier(const Frontier &frontier) const = 0; 26 | 27 | }; 28 | 29 | } 30 | 31 | #endif //ROBO_PLANNER_WS_MAP_H 32 | 33 | 34 | -------------------------------------------------------------------------------- /fael_planner/planner/include/preprocess/topo_graph.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2022/1/10. 3 | // 4 | 5 | #ifndef ROBO_PLANNER_WS_TOPO_GRAPH_H 6 | #define ROBO_PLANNER_WS_TOPO_GRAPH_H 7 | 8 | #include 9 | #include "graph/plan_graph.h" 10 | #include "preprocess/viewpoint_manager.h" 11 | 12 | namespace preprocess { 13 | 14 | class TopoGraph { 15 | public: 16 | typedef std::shared_ptr Ptr; 17 | ros::NodeHandle nh_; 18 | ros::NodeHandle nh_private_; 19 | 20 | ros::Publisher graph_pub_; 21 | 22 | utils::Point3D current_position_; 23 | graph::PlanGraph graph_; 24 | bool is_graph_initialized_; 25 | 26 | std::string frame_id_; 27 | float sample_dist_; 28 | float connectable_range_;//the maximum connectable distance of newly added points during the graph exhibition 29 | float connectable_min_range_; 30 | int connectable_num_;//maximum number of points that every new viewpoint can connect 31 | 32 | std::string each_graph_update_txt_name_; 33 | double sum_graph_update_time_; 34 | int graph_update_num_; 35 | 36 | explicit TopoGraph(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private); 37 | 38 | void getParamsFromRos();// new graph class and set params. 39 | 40 | void setCurrentPosition(const utils::Point3D ¤t_position); 41 | 42 | void addVertex(const Point3D &point); 43 | 44 | void updateTopoGraphByMap2DAndViewpoints(const Map2DManager::Ptr &map_2d_manager,const ViewpointManager::Ptr &viewpoint_manager, const Ufomap::Ptr &frontier_map); 45 | 46 | void initTopoGraphByCurrentPositionAndReprePoints(const GridMap2D &grid_map_2d, const Point3D ¤t_position, const Point3DSet &repre_points); 47 | 48 | void growingByMap2dAndSamplePoints(const GridMap2D &grid_map_2d, const Point3DSet &sample_points); 49 | 50 | void pubGraphMarkers() const; 51 | 52 | visualization_msgs::MarkerArray generateTopoGraphMarkers() const; 53 | 54 | 55 | }; 56 | 57 | } 58 | 59 | #endif //ROBO_PLANNER_WS_TOPO_GRAPH_H 60 | -------------------------------------------------------------------------------- /fael_planner/planner/include/topo_planner/topo_planner.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2022/1/10. 3 | // 4 | 5 | #ifndef ROBO_PLANNER_WS_TOPO_PLANNER_H 6 | #define ROBO_PLANNER_WS_TOPO_PLANNER_H 7 | 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | 17 | #include 18 | #include 19 | #include 20 | #include 21 | 22 | #include 23 | #include 24 | #include 25 | #include 26 | #include 27 | #include 28 | 29 | #include "preprocess/preprocess.h" 30 | #include "rapid_cover_planner/rapid_cover_planner.h" 31 | 32 | namespace topo_planner{ 33 | 34 | class TopoPlanner{ 35 | public: 36 | typedef actionlib::SimpleActionServer ExplorerPlannerServer; 37 | 38 | ros::NodeHandle nh_; 39 | ros::NodeHandle nh_private_; 40 | 41 | ros::Subscriber explore_finish_sub_; 42 | 43 | ros::Publisher iteration_time_pub_; 44 | 45 | ExplorerPlannerServer planner_action_server_; 46 | int planner_goal_id_; 47 | 48 | ros::Timer preprocess_timer_; 49 | ros::Timer msgs_timer_; 50 | bool preprocess_inited_; 51 | 52 | ros::Publisher topo_planner_msgs_pub_; 53 | 54 | preprocess::Preprocess::Ptr elements_; 55 | 56 | rapid_cover_planner::RapidCoverPlanner::Ptr planner_; 57 | 58 | TopoPlanner(ros::NodeHandle &nh, ros::NodeHandle &nh_private); 59 | 60 | void plannerCallback(const control_planner_interface::ExplorerPlannerGoalConstPtr &goal); 61 | 62 | std::vector wayPoseGeneration(rapid_cover_planner::Path &path); 63 | 64 | bool isExplorationFinish(); 65 | 66 | bool isCurrentGoalScanned(); 67 | 68 | void topo_planner_msgs_publish(); 69 | 70 | void explorationFinishCallback(const std_msgs::BoolConstPtr &finish); 71 | 72 | }; 73 | } 74 | 75 | #endif //ROBO_PLANNER_WS_TOPO_PLANNER_H 76 | -------------------------------------------------------------------------------- /fael_planner/planner/include/utils/frontier.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2022/1/9. 3 | // 4 | 5 | #ifndef ROBO_PLANNER_WS_FRONTIER_H 6 | #define ROBO_PLANNER_WS_FRONTIER_H 7 | 8 | #include "point3d.h" 9 | 10 | namespace utils { 11 | using Frontier = Point3D; 12 | 13 | using FrontierSet = Point3DSet; //a collection representing frontier, can be well indexed and stored 14 | template 15 | using FrontierMap = Point3DMap; 16 | using FrontierQueue = Point3DQueue; 17 | } 18 | 19 | 20 | #endif //ROBO_PLANNER_WS_FRONTIER_H -------------------------------------------------------------------------------- /fael_planner/planner/include/utils/viewpoint.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2022/1/10. 3 | // 4 | 5 | #ifndef ROBO_PLANNER_WS_VIEWPOINT_H 6 | #define ROBO_PLANNER_WS_VIEWPOINT_H 7 | 8 | #include "point3d.h" 9 | 10 | namespace utils { 11 | using Viewpoint = Point3D; 12 | 13 | using ViewpointSet = Point3DSet; 14 | template 15 | using ViewpointMap = Point3DMap; 16 | using ViewpointQueue = Point3DQueue; 17 | } 18 | 19 | #endif //ROBO_PLANNER_WS_VIEWPOINT_H 20 | 21 | -------------------------------------------------------------------------------- /fael_planner/planner/launch/planner.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 | -------------------------------------------------------------------------------- /fael_planner/planner/msg/EdgePair.msg: -------------------------------------------------------------------------------- 1 | 2 | int32 edge_id 3 | IdPointPair begin_point 4 | IdPointPair end_point -------------------------------------------------------------------------------- /fael_planner/planner/msg/IdPointPair.msg: -------------------------------------------------------------------------------- 1 | int32 id 2 | geometry_msgs/Point point -------------------------------------------------------------------------------- /fael_planner/planner/msg/PreprocessMsgs.msg: -------------------------------------------------------------------------------- 1 | 2 | Header header 3 | 4 | ufomap_manager/UfomapWithFrontiers ufomap_with_frontiers 5 | 6 | ViewpointsWithFrontiers[] viewpoint_frontiers_set 7 | 8 | RoadMapMsg road_map_msg 9 | -------------------------------------------------------------------------------- /fael_planner/planner/msg/RoadMapMsg.msg: -------------------------------------------------------------------------------- 1 | 2 | IdPointPair[] id_point_pair_list 3 | EdgePair[] edge_pair_list -------------------------------------------------------------------------------- /fael_planner/planner/msg/ViewpointsWithFrontiers.msg: -------------------------------------------------------------------------------- 1 | 2 | geometry_msgs/Point view_point 3 | ufomap_manager/CellCode[] frontiers -------------------------------------------------------------------------------- /fael_planner/planner/resource/topo_planner_1.yaml: -------------------------------------------------------------------------------- 1 | 2 | # 总类 3 | frame_id: world 4 | robot_base_frame_id: base_link 5 | 6 | UFOMap: 7 | # robot size configuration 8 | robot_height: 0.8 9 | robot_bottom: 0.05 10 | sensor_height: 0.45 11 | 12 | # ufomap map configuration 13 | resolution: 0.4 14 | depth_levels: 16 15 | max_range: 12.0 16 | 17 | frame_id: world # 18 | navigation_frame_id: world 19 | robot_base_frame_id: base_link 20 | insert_discrete: true 21 | insert_depth: 0 22 | simple_ray_casting: false 23 | early_stopping: 0 24 | clear_robot_enabled: false 25 | 26 | frontier_depth: 0 27 | pub_rate: 1 28 | scan_voxel_size: 0.1 29 | 30 | min_x: -1000.0 31 | min_y: -1000.0 32 | max_x: 1000 33 | max_y: 1000 34 | 35 | GridMap2D: 36 | frame_id: world 37 | grid_size: 0.15 38 | inflate_radius: 0.3 39 | inflate_empty_radius: 0.3 40 | lower_z: 0.2 41 | connectivity_thre: 0.1 42 | 43 | 44 | ViewpointManager: 45 | frame_id: world 46 | sample_dist: 1.0 47 | frontier_dist: 15.0 48 | viewpoint_gain_thre: 2.0 49 | 50 | 51 | Roadmap: 52 | frame_id: world 53 | sample_dist: 1.0 54 | connectable_range: 3 55 | connectable_num: 3 56 | 57 | RapidCoverPlanner: 58 | max_tour_point_num: 100 59 | viewpoint_ignore_thre: 0.5 60 | local_range: 24.0 61 | frontier_gain: 100.0 62 | tourpoint_ignore_thre: 0.8 63 | tourpoint_ignore_distance: 3.0 64 | is_directory: true 65 | alpha: 0.9 66 | 67 | 68 | 69 | -------------------------------------------------------------------------------- /fael_planner/planner/src/topo_planner/topo_planner_node.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/11/16. 3 | // 4 | 5 | #include 6 | 7 | #include "topo_planner/topo_planner.h" 8 | 9 | 10 | int main(int argc, char** argv){ 11 | ros::init(argc,argv,"topo_planner_node"); 12 | ros::NodeHandle nh; 13 | ros::NodeHandle nh_private("~"); 14 | 15 | ROS_INFO_STREAM("start planner"); 16 | 17 | topo_planner::TopoPlanner planner(nh, nh_private); 18 | 19 | ros::spin(); 20 | return 0; 21 | } 22 | -------------------------------------------------------------------------------- /fael_planner/planner/src/tsp_solver/two_opt.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2022/6/7. 3 | // 4 | 5 | #include "../../include/tsp_solver/two_opt.h" 6 | -------------------------------------------------------------------------------- /fael_planner/robot_move/cmu_planner/local_planner/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(local_planner) 3 | 4 | set(CMAKE_BUILD_TYPE Release) 5 | set(BUILD_STATIC_LIBS ON) 6 | set(BUILD_SHARED_LIBS OFF) 7 | set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) 8 | 9 | ## Find catkin macros and libraries 10 | find_package(catkin REQUIRED COMPONENTS 11 | roscpp 12 | std_msgs 13 | sensor_msgs 14 | pcl_ros 15 | ) 16 | 17 | find_package(PCL REQUIRED) 18 | 19 | ################################### 20 | ## catkin specific configuration ## 21 | ################################### 22 | 23 | catkin_package( 24 | CATKIN_DEPENDS 25 | roscpp 26 | std_msgs 27 | sensor_msgs 28 | pcl_ros 29 | ) 30 | 31 | ########### 32 | ## Build ## 33 | ########### 34 | 35 | ## Specify additional locations of header files 36 | ## Your package locations should be listed before other locations 37 | include_directories( 38 | ${catkin_INCLUDE_DIRS} 39 | ${PCL_INCLUDE_DIRS} 40 | "${PROJECT_SOURCE_DIR}/include" 41 | /usr/local/include # Location when using 'make system_install' 42 | /usr/include # More usual location (e.g. when installing using a package) 43 | ) 44 | 45 | ## Specify additional locations for library files 46 | link_directories( 47 | /usr/local/lib # Location when using 'make system_install' 48 | /usr/lib # More usual location (e.g. when installing using a package) 49 | ) 50 | 51 | ## Declare executables 52 | add_executable(localPlanner src/localPlanner.cpp) 53 | add_executable(pathFollower src/pathFollower.cpp) 54 | 55 | ## Specify libraries to link a library or executable target against 56 | target_link_libraries(localPlanner ${catkin_LIBRARIES} ${PCL_LIBRARIES}) 57 | target_link_libraries(pathFollower ${catkin_LIBRARIES} ${PCL_LIBRARIES}) 58 | 59 | #install(TARGETS localPlanner pathFollower 60 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 61 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 62 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 63 | #) 64 | # 65 | #install(DIRECTORY launch 66 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch 67 | #) 68 | #install(DIRECTORY paths 69 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/paths 70 | #) 71 | -------------------------------------------------------------------------------- /fael_planner/robot_move/cmu_planner/local_planner/package.xml: -------------------------------------------------------------------------------- 1 | 2 | local_planner 3 | 0.0.1 4 | Local Planner 5 | Ji Zhang 6 | BSD 7 | 8 | catkin 9 | 10 | roscpp 11 | std_msgs 12 | sensor_msgs 13 | message_filters 14 | pcl_ros 15 | 16 | roscpp 17 | std_msgs 18 | sensor_msgs 19 | message_filters 20 | pcl_ros 21 | 22 | -------------------------------------------------------------------------------- /fael_planner/robot_move/cmu_planner/terrain_analysis/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(terrain_analysis) 3 | 4 | set(CMAKE_BUILD_TYPE Release) 5 | set(BUILD_STATIC_LIBS ON) 6 | set(BUILD_SHARED_LIBS OFF) 7 | set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) 8 | 9 | ## Find catkin macros and libraries 10 | find_package(catkin REQUIRED COMPONENTS 11 | roscpp 12 | std_msgs 13 | sensor_msgs 14 | pcl_ros 15 | ) 16 | 17 | find_package(OpenCV REQUIRED) 18 | find_package(PCL REQUIRED) 19 | 20 | ################################### 21 | ## catkin specific configuration ## 22 | ################################### 23 | 24 | catkin_package( 25 | CATKIN_DEPENDS 26 | roscpp 27 | std_msgs 28 | sensor_msgs 29 | pcl_ros 30 | ) 31 | 32 | ########### 33 | ## Build ## 34 | ########### 35 | 36 | ## Specify additional locations of header files 37 | ## Your package locations should be listed before other locations 38 | include_directories( 39 | ${catkin_INCLUDE_DIRS} 40 | ${OpenCV_INCLUDE_DIRS} 41 | ${PCL_INCLUDE_DIRS} 42 | "${PROJECT_SOURCE_DIR}/include" 43 | /usr/local/include # Location when using 'make system_install' 44 | /usr/include # More usual location (e.g. when installing using a package) 45 | ) 46 | 47 | ## Specify additional locations for library files 48 | link_directories( 49 | /usr/local/lib # Location when using 'make system_install' 50 | /usr/lib # More usual location (e.g. when installing using a package) 51 | ) 52 | 53 | ## Declare executables 54 | add_executable(terrainAnalysis src/terrainAnalysis.cpp) 55 | 56 | ## Specify libraries to link a library or executable target against 57 | target_link_libraries(terrainAnalysis ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${PCL_LIBRARIES}) 58 | 59 | install(TARGETS terrainAnalysis 60 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 61 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 62 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 63 | ) 64 | 65 | install(DIRECTORY launch 66 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch 67 | ) 68 | -------------------------------------------------------------------------------- /fael_planner/robot_move/cmu_planner/terrain_analysis/launch/terrain_analysis.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 | -------------------------------------------------------------------------------- /fael_planner/robot_move/cmu_planner/terrain_analysis/package.xml: -------------------------------------------------------------------------------- 1 | 2 | terrain_analysis 3 | 0.0.1 4 | Terrain Analysis 5 | Ji Zhang 6 | BSD 7 | 8 | catkin 9 | 10 | roscpp 11 | std_msgs 12 | sensor_msgs 13 | message_filters 14 | pcl_ros 15 | 16 | roscpp 17 | std_msgs 18 | sensor_msgs 19 | message_filters 20 | pcl_ros 21 | 22 | -------------------------------------------------------------------------------- /fael_planner/robot_move/path_execution/launch/path_execution.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 | -------------------------------------------------------------------------------- /fael_planner/robot_move/path_execution/src/path_execution_node.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/12/17. 3 | // 4 | 5 | #include "path_execution/path_execution.h" 6 | 7 | 8 | int main(int argc, char **argv) { 9 | ros::init(argc, argv, "path_execution_node"); 10 | 11 | ros::NodeHandle nh_private("~"); 12 | ros::NodeHandle nh; 13 | 14 | path_execution::PathExecution execute(nh,nh_private); 15 | 16 | ros::spin(); 17 | 18 | return 0; 19 | } -------------------------------------------------------------------------------- /fael_planner/robot_move/traversability_analysis/launch/traversability_analysis_3d.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 | -------------------------------------------------------------------------------- /fael_planner/robot_move/traversability_analysis/msg/TerrainGrid.msg: -------------------------------------------------------------------------------- 1 | uint8 status 2 | 3 | #坐标系都是输入的点云的坐标系,也就是相对于“map”系的坐标 4 | float32 min_z 5 | geometry_msgs/Point32 bottom_point 6 | sensor_msgs/PointCloud2 points 7 | -------------------------------------------------------------------------------- /fael_planner/robot_move/traversability_analysis/msg/TerrainMap.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | float64 min_x 3 | float64 min_y 4 | float64 z_value 5 | float64 grid_size 6 | uint32 grid_width_num 7 | TerrainGrid[] grids -------------------------------------------------------------------------------- /fael_planner/robot_move/traversability_analysis/src/traversability_analysis_node_3d.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/10/22. 3 | // 4 | 5 | #include 6 | 7 | int main(int argc, char **argv) { 8 | ros::init(argc, argv, "terrain_analysis_node"); 9 | 10 | ros::NodeHandle nh_private("~"); 11 | ros::NodeHandle nh; 12 | 13 | traversability_analysis::TerrainMapEmpty traversability_analysis(nh, nh_private); 14 | ros::spin(); 15 | return 0; 16 | } -------------------------------------------------------------------------------- /fael_planner/sensor_conversion/include/cartographer_output.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2022/3/25. 3 | // 4 | 5 | #ifndef ROBO_PLANNER_WS_CARTOGRAPHER_OUTPUT_H 6 | #define ROBO_PLANNER_WS_CARTOGRAPHER_OUTPUT_H 7 | 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | 24 | class CartographerOutput { 25 | public: 26 | ros::NodeHandle nh_; 27 | ros::NodeHandle nh_private_; 28 | tf::TransformListener tf_listener; 29 | ros::Publisher odom_pub; 30 | ros::Publisher reg_pub; 31 | ros::Publisher dwz_cloud_pub; 32 | ros::Subscriber scan_sub; 33 | ros::Timer aligen_timer; 34 | 35 | std::string frame_id; 36 | std::string child_frame_id; 37 | 38 | pcl::VoxelGrid downSizeFilter; 39 | float down_voxel_size; 40 | 41 | std::vector> points_vector; 42 | 43 | CartographerOutput(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private); 44 | 45 | void scanCallback(const sensor_msgs::PointCloud2ConstPtr & scanIn); 46 | 47 | void aligenPoints(const ros::TimerEvent &event); 48 | 49 | }; 50 | 51 | 52 | #endif //ROBO_PLANNER_WS_CARTOGRAPHER_OUTPUT_H 53 | -------------------------------------------------------------------------------- /fael_planner/sensor_conversion/include/slam_simulation/slam_output.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/9/18. 3 | // 4 | #ifndef TOPO_PLANNER_WS_SLAM_OUTPUT_H 5 | #define TOPO_PLANNER_WS_SLAM_OUTPUT_H 6 | 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | 22 | class SlamOutput { 23 | public: 24 | ros::NodeHandle nh_; 25 | ros::NodeHandle nh_private_; 26 | tf::TransformBroadcaster broadcaster; 27 | tf::TransformListener tf_listener; 28 | ros::Publisher odom_pub; 29 | ros::Publisher reg_pub; 30 | ros::Publisher dwz_cloud_pub; 31 | ros::Subscriber odom_sub; 32 | ros::Subscriber scan_sub; 33 | ros::Timer global_down_timer; 34 | 35 | tf::StampedTransform transform; 36 | ros::Rate rate; 37 | 38 | typedef message_filters::sync_policies::ApproximateTime SyncPolicyLocalCloudOdom; 39 | std::shared_ptr> local_cloud_sub_; 40 | std::shared_ptr> local_odom_sub_; 41 | typedef std::shared_ptr> SynchronizerLocalCloudOdom; 42 | SynchronizerLocalCloudOdom sync_local_cloud_odom_; 43 | 44 | std::string frame_id; 45 | std::string child_frame_id; 46 | 47 | bool is_get_first; 48 | 49 | tf::Transform T_B_W ; 50 | 51 | std::vector ST_B_Bi_vec; 52 | double vec_length; 53 | 54 | pcl::VoxelGrid downSizeFilter; 55 | float down_voxel_size; 56 | 57 | SlamOutput(const ros::NodeHandle &nh, const ros::NodeHandle &nh_private); 58 | 59 | void pointCloudOdomCallback(const sensor_msgs::PointCloud2ConstPtr& point_cloud,const nav_msgs::OdometryConstPtr& input); 60 | }; 61 | 62 | 63 | 64 | #endif //TOPO_PLANNER_WS_SLAM_OUTPUT_H 65 | -------------------------------------------------------------------------------- /fael_planner/sensor_conversion/src/slam_output_node.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by hjl on 2021/9/18. 3 | // 4 | 5 | #include "slam_simulation/slam_output.h" 6 | 7 | int main(int argc, char **argv) { 8 | ros::init(argc, argv, "slam_sim_output"); 9 | ros::NodeHandle nh; 10 | ros::NodeHandle nh_private("~"); 11 | 12 | SlamOutput slam_out_put(nh, nh_private); 13 | 14 | ros::spin(); 15 | return 0; 16 | } 17 | -------------------------------------------------------------------------------- /fael_planner/visualization_tools/launch/visualization_tools.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /fael_planner/visualization_tools/msg/ExploredVolumeTime.msg: -------------------------------------------------------------------------------- 1 | 2 | Header header 3 | float64 exploredVolume 4 | float64 timeConsumed -------------------------------------------------------------------------------- /fael_planner/visualization_tools/msg/ExploredVolumeTravedDist.msg: -------------------------------------------------------------------------------- 1 | 2 | Header header 3 | float64 exploredVolume 4 | float64 travedDist -------------------------------------------------------------------------------- /fael_planner/visualization_tools/msg/ExploredVolumeTravedDistTime.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | float64 exploredVolume 3 | float64 travedDist 4 | float64 timeConsumed -------------------------------------------------------------------------------- /fael_planner/visualization_tools/msg/IterationTime.msg: -------------------------------------------------------------------------------- 1 | 2 | Header header 3 | float64 current_time 4 | float64 iterationTime 5 | float64 timeConsumed 6 | -------------------------------------------------------------------------------- /fael_planner/visualization_tools/msg/TravedDistTime.msg: -------------------------------------------------------------------------------- 1 | 2 | Header header 3 | float64 travedDist 4 | float64 timeConsumed -------------------------------------------------------------------------------- /fael_planner/visualization_tools/msg/ViewpointGain.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | int32[] viewpoints_ids 3 | float64[] frontiers_gains 4 | float64[] unmapped_gains -------------------------------------------------------------------------------- /fael_planner/visualization_tools/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | visualization_tools 4 | 0.0.1 5 | Visulization Tools 6 | hjl 7 | TODO 8 | 9 | catkin 10 | 11 | rospy 12 | roscpp 13 | std_msgs 14 | sensor_msgs 15 | pcl_ros 16 | tf 17 | geometry_msgs 18 | nav_msgs 19 | ufomap_manager 20 | message_generation 21 | message_runtime 22 | 23 | pcl_ros 24 | rospy 25 | roscpp 26 | tf 27 | geometry_msgs 28 | nav_msgs 29 | sensor_msgs 30 | std_msgs 31 | ufomap_manager 32 | message_generation 33 | message_runtime 34 | 35 | rospy 36 | roscpp 37 | tf 38 | geometry_msgs 39 | nav_msgs 40 | sensor_msgs 41 | std_msgs 42 | ufomap_manager 43 | pcl_ros 44 | message_generation 45 | message_runtime 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | -------------------------------------------------------------------------------- /files/exploration_data/.gitkeep: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/files/exploration_data/.gitkeep -------------------------------------------------------------------------------- /files/figure/1.jpeg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/files/figure/1.jpeg -------------------------------------------------------------------------------- /files/figure/2.jpeg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/files/figure/2.jpeg -------------------------------------------------------------------------------- /sim_env/10_22outside/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | 3 | project(10_22outside) 4 | 5 | find_package(catkin REQUIRED) 6 | 7 | catkin_package() 8 | 9 | find_package(roslaunch) 10 | 11 | foreach(dir config launch meshes urdf) 12 | install(DIRECTORY ${dir}/ 13 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) 14 | endforeach(dir) 15 | -------------------------------------------------------------------------------- /sim_env/10_22outside/config/joint_names_10_22outside.yaml: -------------------------------------------------------------------------------- 1 | controller_joint_names: ['', ] 2 | -------------------------------------------------------------------------------- /sim_env/10_22outside/export.log: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/sim_env/10_22outside/export.log -------------------------------------------------------------------------------- /sim_env/10_22outside/launch/display.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 7 | 11 | 15 | 20 | -------------------------------------------------------------------------------- /sim_env/10_22outside/launch/gazebo.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 9 | 15 | 20 | -------------------------------------------------------------------------------- /sim_env/10_22outside/meshes/Empty_Link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/sim_env/10_22outside/meshes/Empty_Link.STL -------------------------------------------------------------------------------- /sim_env/10_22outside/meshes/base_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/sim_env/10_22outside/meshes/base_link.STL -------------------------------------------------------------------------------- /sim_env/10_22outside/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 10_22outside 3 | 1.0.0 4 | 5 |

URDF Description package for 10_22outside

6 |

This package contains configuration data, 3D models and launch files 7 | for 10_22outside robot

8 |
9 | TODO 10 | 11 | BSD 12 | catkin 13 | roslaunch 14 | robot_state_publisher 15 | rviz 16 | joint_state_publisher_gui 17 | gazebo 18 | 19 | 20 | 21 |
-------------------------------------------------------------------------------- /sim_env/10_22outside/urdf/10_22outside.csv: -------------------------------------------------------------------------------- 1 | Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity 2 | base_link,84.4335841028867,-1.67939986132453E-13,2.5,0,0,0,4484413.02210824,12727567802.556,-2.91436447932832E-05,5.4931635034149E-07,7044982325.57827,2.10804263755649E-08,19753865073.8754,0,0,0,0,0,0,package://10_22outside/meshes/base_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://10_22outside/meshes/base_link.STL,,围墙-1,坐标系1,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, 3 | Empty_Link,81.2001557000657,6.33535012468957E-14,6.47019507806598,0,0,0,15188176,1574790314.05357,-2.06198995783421E-06,-3.95609131451899E-07,1574790314.05357,2.77283463914843E-07,1487195938.02667,0,0,0,0,0,0,package://10_22outside/meshes/Empty_Link.STL,0.447058823529412,0.729411764705882,0.0509803921568627,1,0,0,0,0,0,0,package://10_22outside/meshes/Empty_Link.STL,,楼房3-12;楼房3-9;楼房3-6;楼房3-3;楼房3-2;楼房3-1;楼房3-10;楼房3-7;楼房3-4;楼房3-11;楼房3-8;楼房3-5;方柱-7;方柱-4;方柱-11;方柱-13;方柱-3;方柱-6;方柱-9;方柱-1;方柱-2;方柱-10;方柱-8;方柱-5;方柱-12;方柱-14,坐标系1,Axis_fixed,fixed,fixed,0,0,0,0,0,0,base_link,0,0,0,,,,,,,,,,,, 4 | -------------------------------------------------------------------------------- /sim_env/10_22room2/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | 3 | project(10_22room2) 4 | 5 | find_package(catkin REQUIRED) 6 | 7 | catkin_package() 8 | 9 | find_package(roslaunch) 10 | 11 | foreach(dir config launch meshes urdf) 12 | install(DIRECTORY ${dir}/ 13 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) 14 | endforeach(dir) 15 | -------------------------------------------------------------------------------- /sim_env/10_22room2/config/joint_names_10_22room2.yaml: -------------------------------------------------------------------------------- 1 | controller_joint_names: ['', ] 2 | -------------------------------------------------------------------------------- /sim_env/10_22room2/export.log: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/sim_env/10_22room2/export.log -------------------------------------------------------------------------------- /sim_env/10_22room2/launch/display.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 7 | 11 | 15 | 20 | -------------------------------------------------------------------------------- /sim_env/10_22room2/launch/gazebo.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 9 | 15 | 20 | -------------------------------------------------------------------------------- /sim_env/10_22room2/meshes/base_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/sim_env/10_22room2/meshes/base_link.STL -------------------------------------------------------------------------------- /sim_env/10_22room2/meshes/fixed1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/sim_env/10_22room2/meshes/fixed1.STL -------------------------------------------------------------------------------- /sim_env/10_22room2/meshes/fixed2.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SYSU-RoboticsLab/FAEL/a180b4129efe8fa3b27e877cb3417d1189b622ee/sim_env/10_22room2/meshes/fixed2.STL -------------------------------------------------------------------------------- /sim_env/10_22room2/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 10_22room2 3 | 1.0.0 4 | 5 |

URDF Description package for 10_22room2

6 |

This package contains configuration data, 3D models and launch files 7 | for 10_22room2 robot

8 |
9 | TODO 10 | 11 | BSD 12 | catkin 13 | roslaunch 14 | robot_state_publisher 15 | rviz 16 | joint_state_publisher_gui 17 | gazebo 18 | 19 | 20 | 21 |
-------------------------------------------------------------------------------- /sim_env/10_22room2/urdf/10_22room2.csv: -------------------------------------------------------------------------------- 1 | Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity 2 | base_link,48.8921428822432,-1.17139840239803E-14,2.5,0,0,0,1935098.44949343,2360370034.88366,3.86745731221733E-06,1.0457124529494E-07,2059683974.11966,2.29155435960138E-07,4411991098.7971,0,0,0,0,0,0,package://10_22room2/meshes/base_link.STL,0.749019607843137,0.529411764705882,0.149019607843137,1,0,0,0,0,0,0,package://10_22room2/meshes/base_link.STL,,room4-1,坐标系1,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, 3 | fixed1,16.9585875235413,8.62052242418681E-16,0.742247005824651,0,0,0,109723.569326841,67219.3350585608,3.25145099749031E-12,-6.65008815905125E-13,353673.368090466,-7.74949548976167E-13,373444.358088869,0,0,0,0,0,0,package://10_22room2/meshes/fixed1.STL,1,0.988235294117647,0.92156862745098,1,0,0,0,0,0,0,package://10_22room2/meshes/fixed1.STL,,desk3-1;cabinet2-3;cabinet2-2;desk3-2;cabinet2-4;cabinet2-5,坐标系1,Axis_fixed1,fixed1,fixed,0,0,0,0,0,0,base_link,0,0,0,,,,,,,,,,,, 4 | fixed2,67,0.469465648855002,1,0,0,0,733600,7261874.66666663,1.95439546051557E-09,8.46730093447453E-11,3369538.66666667,9.64049084004231E-11,10142346.6666666,0,0,0,0,0,0,package://10_22room2/meshes/fixed2.STL,0.149019607843137,0.909803921568627,0.592156862745098,1,0,0,0,0,0,0,package://10_22room2/meshes/fixed2.STL,,隔断1-12;隔断1-11;隔断1-10;隔断1-13;隔断1-14;隔断1-3;隔断1-2;隔断1-1;隔断1-4;隔断1-5,坐标系1,Axis_fixed2,fixed2,fixed,0,0,0,0,0,0,base_link,0,0,0,,,,,,,,,,,, 5 | --------------------------------------------------------------------------------