├── README.md ├── custom_controllers ├── ackermann-drive-teleop │ ├── CMakeLists.txt │ ├── LICENSE │ ├── README.md │ ├── launch │ │ └── ackermann_drive_joyop.launch │ ├── package.xml │ └── scripts │ │ ├── joyop.py │ │ └── keyop.py ├── obstacle_detector │ ├── .gitignore │ ├── CMakeLists.txt │ ├── README.md │ ├── icons │ │ └── classes │ │ │ ├── Obstacle Extractor.png │ │ │ ├── Obstacle Publisher.png │ │ │ ├── Obstacle Tracker.png │ │ │ ├── Obstacles.png │ │ │ └── Scans Merger.png │ ├── include │ │ └── obstacle_detector │ │ │ ├── displays │ │ │ ├── circle_visual.h │ │ │ ├── obstacles_display.h │ │ │ └── segment_visual.h │ │ │ ├── obstacle_extractor.h │ │ │ ├── obstacle_publisher.h │ │ │ ├── obstacle_tracker.h │ │ │ ├── panels │ │ │ ├── obstacle_extractor_panel.h │ │ │ ├── obstacle_publisher_panel.h │ │ │ ├── obstacle_tracker_panel.h │ │ │ └── scans_merger_panel.h │ │ │ ├── scans_merger.h │ │ │ └── utilities │ │ │ ├── circle.h │ │ │ ├── figure_fitting.h │ │ │ ├── kalman.h │ │ │ ├── math_utilities.h │ │ │ ├── point.h │ │ │ ├── point_set.h │ │ │ ├── segment.h │ │ │ └── tracked_obstacle.h │ ├── launch │ │ ├── ACE.launch │ │ ├── demo.launch │ │ ├── nodelets.launch │ │ └── nodes.launch │ ├── msg │ │ ├── CircleObstacle.msg │ │ ├── Obstacles.msg │ │ └── SegmentObstacle.msg │ ├── nodelet_plugins.xml │ ├── package.xml │ ├── resources │ │ ├── ObstacleDetector.pdf │ │ ├── Using hokuyo_node with udev.txt │ │ ├── obstacle_detector.rviz │ │ ├── play.png │ │ ├── scans_demo.bag │ │ └── stop.png │ ├── rviz_plugins.xml │ └── src │ │ ├── displays │ │ ├── circle_visual.cpp │ │ ├── obstacles_display.cpp │ │ └── segment_visual.cpp │ │ ├── nodelets │ │ ├── obstacle_extractor_nodelet.cpp │ │ ├── obstacle_publisher_nodelet.cpp │ │ ├── obstacle_tracker_nodelet.cpp │ │ └── scans_merger_nodelet.cpp │ │ ├── nodes │ │ ├── obstacle_extractor_node.cpp │ │ ├── obstacle_publisher_node.cpp │ │ ├── obstacle_tracker_node.cpp │ │ └── scans_merger_node.cpp │ │ ├── obstacle_extractor.cpp │ │ ├── obstacle_publisher.cpp │ │ ├── obstacle_tracker.cpp │ │ ├── panels │ │ ├── obstacle_extractor_panel.cpp │ │ ├── obstacle_publisher_panel.cpp │ │ ├── obstacle_tracker_panel.cpp │ │ └── scans_merger_panel.cpp │ │ └── scans_merger.cpp └── teb_local_planner_tutorials │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── README.md │ ├── cfg │ ├── amcl_params.yaml │ ├── carlike │ │ ├── costmap_common_params.yaml │ │ ├── global_costmap_params.yaml │ │ ├── local_costmap_params.yaml │ │ └── teb_local_planner_params.yaml │ ├── diff_drive │ │ ├── costmap_common_params.yaml │ │ ├── costmap_converter_params.yaml │ │ ├── dyn_obst │ │ │ ├── costmap_converter_params.yaml │ │ │ ├── global_costmap_params.yaml │ │ │ ├── local_costmap_params.yaml │ │ │ └── teb_local_planner_params.yaml │ │ ├── global_costmap_params.yaml │ │ ├── local_costmap_params.yaml │ │ └── teb_local_planner_params.yaml │ ├── omnidir │ │ ├── costmap_common_params.yaml │ │ ├── costmap_converter_params.yaml │ │ ├── global_costmap_params.yaml │ │ ├── local_costmap_params.yaml │ │ └── teb_local_planner_params.yaml │ ├── rviz_navigation.rviz │ └── rviz_navigation_cc.rviz │ ├── launch │ ├── dyn_obst_corridor_scenario.launch │ ├── dyn_obst_costmap_conversion.launch │ ├── robot_carlike_in_stage.launch │ ├── robot_diff_drive_in_stage.launch │ ├── robot_diff_drive_in_stage_costmap_conversion.launch │ └── robot_omnidir_in_stage.launch │ ├── maps │ ├── corridor.png │ ├── corridor.yaml │ ├── empty_box.png │ ├── empty_box.yaml │ ├── maze.png │ └── maze.yaml │ ├── package.xml │ ├── scripts │ ├── cmd_vel_to_ackermann_drive.py │ ├── export_to_mat.py │ ├── export_to_svg.py │ ├── move_obstacle.py │ ├── publish_dynamic_obstacle.py │ ├── publish_ground_truth_obstacles.py │ ├── publish_test_obstacles.py │ ├── publish_viapoints.py │ ├── visualize_obstacle_velocity_profile.py │ └── visualize_velocity_profile.py │ └── stage │ ├── corridor.world │ ├── empty_box.world │ ├── maze_carlike.world │ ├── maze_diff_drive.world │ ├── maze_omnidir.world │ └── robots │ ├── carlike_robot.inc │ ├── diff_drive_robot.inc │ ├── diff_drive_robot_gps.inc │ ├── obstacle.inc │ └── omnidir_robot.inc ├── docs ├── coordinates_wheels.jpg ├── gazebo.gif └── rviz.gif ├── git_sync.sh ├── rbcar_common ├── .gitignore ├── LICENSE ├── README.md ├── rbcar_common │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml ├── rbcar_description │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── rbcar.rviz │ │ ├── rbcar_rviz.launch │ │ └── rbcar_state_robot.launch │ ├── meshes │ │ ├── bases │ │ │ ├── rbcar_chassis.dae │ │ │ ├── rbcar_chassis.stl │ │ │ └── rbcar_chassis_v2.STL │ │ └── wheels │ │ │ ├── rbcar_wheel1.dae │ │ │ ├── rbcar_wheel1.stl │ │ │ ├── rbcar_wheel2.dae │ │ │ └── rbcar_wheel2.stl │ ├── mybot.plugins.xacro │ ├── package.xml │ ├── rbcar.urdf.xacro │ ├── robots │ │ └── rbcar.urdf.xacro │ └── urdf │ │ ├── bases │ │ ├── rbcar_base.gazebo.xacro │ │ ├── rbcar_base.urdf.xacro │ │ └── to-be-deleted │ │ │ └── rbcar_base.urdf.xacro │ │ └── wheels │ │ ├── suspension_wheel.urdf.xacro │ │ └── to-be-deleted │ │ └── suspension_wheel.urdf.xacro ├── rbcar_localization │ ├── CMakeLists.txt │ ├── launch │ │ ├── amcl.launch │ │ ├── hector_slam.launch │ │ ├── laserscan_from_pointcloud.launch │ │ ├── map_server.launch │ │ └── slam_gmapping.launch │ ├── maps │ │ ├── map.pgm │ │ ├── map.yaml │ │ ├── test.pgm │ │ └── test.yaml │ └── package.xml ├── rbcar_navigation │ ├── CMakeLists.txt │ ├── config │ │ ├── costmap_common_params.yaml │ │ ├── global_costmap_params_map.yaml │ │ ├── global_planner_params.yaml │ │ ├── local_costmap_params.yaml │ │ ├── move_base_params.yaml │ │ └── teb_local_planner_params.yaml │ ├── launch │ │ ├── move_base_TEB.launch │ │ └── move_base_mapping.launch │ └── package.xml ├── rbcar_pad │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── ps3.yaml │ │ ├── ps4.yaml │ │ └── rbcar_pad.launch │ ├── package.xml │ └── src │ │ └── rbcar_pad.cpp ├── robotnik_msgs │ ├── .gitignore │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── README.md │ ├── action │ │ └── SetElevator.action │ ├── msg │ │ ├── AlarmSensor.msg │ │ ├── Alarms.msg │ │ ├── Axis.msg │ │ ├── BatteryDockingStatus.msg │ │ ├── BatteryDockingStatusStamped.msg │ │ ├── BatteryStatus.msg │ │ ├── BatteryStatusStamped.msg │ │ ├── BoolArray.msg │ │ ├── Cartesian_Euler_pose.msg │ │ ├── Data.msg │ │ ├── ElevatorAction.msg │ │ ├── ElevatorStatus.msg │ │ ├── Interfaces.msg │ │ ├── InverterStatus.msg │ │ ├── LaserMode.msg │ │ ├── LaserStatus.msg │ │ ├── MotorHeadingOffset.msg │ │ ├── MotorPID.msg │ │ ├── MotorStatus.msg │ │ ├── MotorsStatus.msg │ │ ├── MotorsStatusDifferential.msg │ │ ├── OdomCalibrationStatus.msg │ │ ├── OdomCalibrationStatusStamped.msg │ │ ├── OdomManualCalibrationStatus.msg │ │ ├── OdomManualCalibrationStatusStamped.msg │ │ ├── Pose2DArray.msg │ │ ├── Pose2DStamped.msg │ │ ├── PresenceSensor.msg │ │ ├── PresenceSensorArray.msg │ │ ├── QueryAlarm.msg │ │ ├── Register.msg │ │ ├── Registers.msg │ │ ├── ReturnMessage.msg │ │ ├── RobotnikMotorsStatus.msg │ │ ├── SafetyModuleStatus.msg │ │ ├── State.msg │ │ ├── StringArray.msg │ │ ├── StringStamped.msg │ │ ├── SubState.msg │ │ ├── alarmmonitor.msg │ │ ├── alarmsmonitor.msg │ │ ├── encoders.msg │ │ ├── inputs_outputs.msg │ │ ├── named_input_output.msg │ │ ├── named_inputs_outputs.msg │ │ └── ptz.msg │ ├── package.xml │ └── srv │ │ ├── GetBool.srv │ │ ├── GetMotorsHeadingOffset.srv │ │ ├── GetPOI.srv │ │ ├── GetPTZ.srv │ │ ├── InsertTask.srv │ │ ├── QueryAlarms.srv │ │ ├── ResetFromSubState.srv │ │ ├── SetBuzzer.srv │ │ ├── SetByte.srv │ │ ├── SetElevator.srv │ │ ├── SetEncoderTurns.srv │ │ ├── SetLaserMode.srv │ │ ├── SetMotorMode.srv │ │ ├── SetMotorPID.srv │ │ ├── SetMotorStatus.srv │ │ ├── SetNamedDigitalOutput.srv │ │ ├── SetString.srv │ │ ├── SetTransform.srv │ │ ├── ack_alarm.srv │ │ ├── axis_record.srv │ │ ├── enable_disable.srv │ │ ├── get_alarms.srv │ │ ├── get_digital_input.srv │ │ ├── get_modbus_register.srv │ │ ├── get_mode.srv │ │ ├── home.srv │ │ ├── set_CartesianEuler_pose.srv │ │ ├── set_analog_output.srv │ │ ├── set_digital_output.srv │ │ ├── set_float_value.srv │ │ ├── set_height.srv │ │ ├── set_modbus_register.srv │ │ ├── set_mode.srv │ │ ├── set_named_digital_output.srv │ │ ├── set_odometry.srv │ │ └── set_ptz.srv └── robotnik_sensors │ ├── .gitignore │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── README.md │ ├── launch │ ├── view_sensor.launch │ └── view_sensor.urdf.xacro │ ├── meshes │ ├── antenna_3GO16.dae │ ├── antenna_3GO16.stl │ ├── asus_xtion_pro_live.dae │ ├── asus_xtion_pro_live.png │ ├── axis_m5013.dae │ ├── axis_m5013.stl │ ├── axis_m5525.dae │ ├── axis_m5525.stl │ ├── axis_p5512.dae │ ├── axis_p5512.stl │ ├── axis_q8641_n1-1.STL │ ├── axis_q8641_n2-1.STL │ ├── benewake_ce30.stl │ ├── camera_axis_p5514.dae │ ├── camera_axis_p5514.stl │ ├── camera_axis_q8641.STL │ ├── flir_ptu_5_base.stl │ ├── flir_ptu_5_body.stl │ ├── flir_ptu_5_stand.stl │ ├── fotonic_e.stl │ ├── hokuyo.png │ ├── hokuyo3d.dae │ ├── hokuyo3d.jpg │ ├── hokuyo3d.stl │ ├── hokuyo_urg_04lx.dae │ ├── hokuyo_urg_04lx.stl │ ├── hokuyo_ust_10lx.dae │ ├── hokuyo_ust_20lx.dae │ ├── hokuyo_utm_30lx.dae │ ├── hokuyo_utm_30lx.stl │ ├── intel_d435.dae │ ├── intel_d435.stl │ ├── intel_r430.dae │ ├── intel_r430.stl │ ├── kinect.dae │ ├── kinect.jpg │ ├── kinect.tga │ ├── kinectv2.dae │ ├── kinectv2.stl │ ├── kinectv2_nobase.dae │ ├── kinectv2_nobase.stl │ ├── orbbec_astra.dae │ ├── orbbec_astra.stl │ ├── ouster1.STL │ ├── pointgrey_bumblebee2.dae │ ├── rplidar.dae │ ├── rplidar_a2.dae │ ├── rplidar_a2.stl │ ├── rs_bpearl.dae │ ├── rs_bpearl.stl │ ├── rslidar.dae │ ├── rslidar.stl │ ├── rslidar_mems.stl │ ├── sick_microscan3.dae │ ├── sick_microscan3.stl │ ├── sick_s300.dae │ ├── sick_s300.stl │ ├── sick_s3000.dae │ ├── sick_s3000.stl │ ├── sick_tim551.dae │ ├── sick_tim551.stl │ ├── sick_tim571.dae │ ├── sick_tim571.stl │ ├── teraranger_tr_duo.dae │ ├── teraranger_tr_duo.stl │ ├── ueye_cp_gige.dae │ ├── ueye_cp_gige.stl │ ├── velodyne_vlp16.dae │ ├── velodyne_vlp16.stl │ ├── ydlidar_4f.dae │ ├── ydlidar_4f.png │ ├── zed.stl │ ├── zed2.stl │ └── zedm.stl │ ├── package.xml │ └── urdf │ ├── all_sensors.urdf.xacro │ ├── asus_xtion_pro.urdf.xacro │ ├── axis.urdf.xacro │ ├── axis_m5013.urdf.xacro │ ├── axis_m5525.urdf.xacro │ ├── axis_q8641.urdf.xacro │ ├── benewake_ce30.urdf.xacro │ ├── flir_ptu_5.urdf.xacro │ ├── fotonic_e.urdf.xacro │ ├── gps.urdf.xacro │ ├── gps_with_mast.urdf.xacro │ ├── hokuyo3d.urdf.xacro │ ├── hokuyo_urg04lx.urdf.xacro │ ├── hokuyo_ust10lx.urdf.xacro │ ├── hokuyo_ust20lx.urdf.xacro │ ├── hokuyo_utm30lx.urdf.xacro │ ├── imu.urdf.xacro │ ├── imu_hector_plugin.urdf.xacro │ ├── intel_d435.urdf.xacro │ ├── intel_r430.urdf.xacro │ ├── kinect.urdf.xacro │ ├── kinectv2.urdf.xacro │ ├── orbbec_astra.urdf.xacro │ ├── ouster1.urdf.xacro │ ├── pointgrey_bumblebee2.urdf.xacro │ ├── roboteq_mgs.urdf.xacro │ ├── rplidar.urdf.xacro │ ├── rplidar_a2.urdf.xacro │ ├── rs_bpearl.urdf.xacro │ ├── rslidar.urdf.xacro │ ├── rslidar_mems.urdf.xacro │ ├── rubedos_viper.urdf.xacro │ ├── sick_microscan3.urdf.xacro │ ├── sick_s300.urdf.xacro │ ├── sick_s3000.urdf.xacro │ ├── sick_tim551.urdf.xacro │ ├── sick_tim571.urdf.xacro │ ├── teraranger_tr_duo.urdf.xacro │ ├── ueye_cp_gige.urdf.xacro │ ├── velodyne_vlp16.urdf.xacro │ ├── ydlidar_4f.urdf.xacro │ └── zed.urdf.xacro ├── rbcar_sim ├── .gitignore ├── LICENSE ├── README.md ├── rbcar_control │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── rbcar_control.yaml │ │ └── twist_mux.yaml │ ├── launch │ │ └── rbcar_control.launch │ └── package.xml ├── rbcar_gazebo │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── rbcar.launch │ │ └── rbcar_gs.launch │ ├── package.xml │ └── worlds │ │ ├── circuit.world │ │ ├── rbcar.world │ │ ├── rbcar_gs.world │ │ ├── road.world │ │ ├── roadworld.world │ │ ├── simple_city.world │ │ └── vrc_task3_firehose_start.world ├── rbcar_joystick │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── ps3.yaml │ │ └── rbcar_joystick.launch │ ├── package.xml │ └── src │ │ └── rbcar_joystick.cpp ├── rbcar_robot_control │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ └── rbcar.yaml │ ├── launch │ │ └── rbcar_robot_control.launch │ ├── package.xml │ └── src │ │ └── rbcar_robot_control.cpp └── rbcar_sim_bringup │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── README.md │ ├── launch │ ├── ekf_nodes.launch │ ├── my_laser_config.yaml │ ├── my_laser_filter.launch │ ├── navsat_transform_node.launch │ ├── purepursuit.launch │ ├── purepursuit_marker.launch │ ├── rbcar_complete.launch │ └── rbcar_complete_gs.launch │ └── package.xml └── rbcar_viz ├── CHANGELOG.rst ├── CMakeLists.txt ├── launch ├── view_model.launch └── view_robot.launch ├── package.xml └── rviz ├── demo_robot_mapping.rviz ├── model.rviz └── robot.rviz /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/README.md -------------------------------------------------------------------------------- /custom_controllers/ackermann-drive-teleop/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/ackermann-drive-teleop/CMakeLists.txt -------------------------------------------------------------------------------- /custom_controllers/ackermann-drive-teleop/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/ackermann-drive-teleop/LICENSE -------------------------------------------------------------------------------- /custom_controllers/ackermann-drive-teleop/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/ackermann-drive-teleop/README.md -------------------------------------------------------------------------------- /custom_controllers/ackermann-drive-teleop/launch/ackermann_drive_joyop.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/ackermann-drive-teleop/launch/ackermann_drive_joyop.launch -------------------------------------------------------------------------------- /custom_controllers/ackermann-drive-teleop/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/ackermann-drive-teleop/package.xml -------------------------------------------------------------------------------- /custom_controllers/ackermann-drive-teleop/scripts/joyop.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/ackermann-drive-teleop/scripts/joyop.py -------------------------------------------------------------------------------- /custom_controllers/ackermann-drive-teleop/scripts/keyop.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/ackermann-drive-teleop/scripts/keyop.py -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/.gitignore: -------------------------------------------------------------------------------- 1 | CMakeLists.txt.user 2 | *~ 3 | -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/CMakeLists.txt -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/README.md -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/icons/classes/Obstacle Extractor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/icons/classes/Obstacle Extractor.png -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/icons/classes/Obstacle Publisher.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/icons/classes/Obstacle Publisher.png -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/icons/classes/Obstacle Tracker.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/icons/classes/Obstacle Tracker.png -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/icons/classes/Obstacles.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/icons/classes/Obstacles.png -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/icons/classes/Scans Merger.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/icons/classes/Scans Merger.png -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/displays/circle_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/displays/circle_visual.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/displays/obstacles_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/displays/obstacles_display.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/displays/segment_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/displays/segment_visual.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/obstacle_extractor.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/obstacle_extractor.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/obstacle_publisher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/obstacle_publisher.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/obstacle_tracker.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/obstacle_tracker.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/panels/obstacle_extractor_panel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/panels/obstacle_extractor_panel.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/panels/obstacle_publisher_panel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/panels/obstacle_publisher_panel.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/panels/obstacle_tracker_panel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/panels/obstacle_tracker_panel.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/panels/scans_merger_panel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/panels/scans_merger_panel.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/scans_merger.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/scans_merger.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/utilities/circle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/utilities/circle.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/utilities/figure_fitting.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/utilities/figure_fitting.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/utilities/kalman.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/utilities/kalman.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/utilities/math_utilities.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/utilities/math_utilities.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/utilities/point.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/utilities/point.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/utilities/point_set.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/utilities/point_set.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/utilities/segment.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/utilities/segment.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/include/obstacle_detector/utilities/tracked_obstacle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/include/obstacle_detector/utilities/tracked_obstacle.h -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/launch/ACE.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/launch/ACE.launch -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/launch/demo.launch -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/launch/nodelets.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/launch/nodelets.launch -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/launch/nodes.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/launch/nodes.launch -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/msg/CircleObstacle.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/msg/CircleObstacle.msg -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/msg/Obstacles.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/msg/Obstacles.msg -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/msg/SegmentObstacle.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/msg/SegmentObstacle.msg -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/nodelet_plugins.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/nodelet_plugins.xml -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/package.xml -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/resources/ObstacleDetector.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/resources/ObstacleDetector.pdf -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/resources/Using hokuyo_node with udev.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/resources/Using hokuyo_node with udev.txt -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/resources/obstacle_detector.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/resources/obstacle_detector.rviz -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/resources/play.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/resources/play.png -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/resources/scans_demo.bag: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/resources/scans_demo.bag -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/resources/stop.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/resources/stop.png -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/rviz_plugins.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/rviz_plugins.xml -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/displays/circle_visual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/displays/circle_visual.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/displays/obstacles_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/displays/obstacles_display.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/displays/segment_visual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/displays/segment_visual.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/nodelets/obstacle_extractor_nodelet.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/nodelets/obstacle_extractor_nodelet.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/nodelets/obstacle_publisher_nodelet.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/nodelets/obstacle_publisher_nodelet.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/nodelets/obstacle_tracker_nodelet.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/nodelets/obstacle_tracker_nodelet.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/nodelets/scans_merger_nodelet.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/nodelets/scans_merger_nodelet.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/nodes/obstacle_extractor_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/nodes/obstacle_extractor_node.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/nodes/obstacle_publisher_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/nodes/obstacle_publisher_node.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/nodes/obstacle_tracker_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/nodes/obstacle_tracker_node.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/nodes/scans_merger_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/nodes/scans_merger_node.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/obstacle_extractor.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/obstacle_extractor.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/obstacle_publisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/obstacle_publisher.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/obstacle_tracker.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/obstacle_tracker.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/panels/obstacle_extractor_panel.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/panels/obstacle_extractor_panel.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/panels/obstacle_publisher_panel.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/panels/obstacle_publisher_panel.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/panels/obstacle_tracker_panel.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/panels/obstacle_tracker_panel.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/panels/scans_merger_panel.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/panels/scans_merger_panel.cpp -------------------------------------------------------------------------------- /custom_controllers/obstacle_detector/src/scans_merger.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/obstacle_detector/src/scans_merger.cpp -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/CHANGELOG.rst -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/CMakeLists.txt -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/README.md -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/amcl_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/amcl_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/carlike/costmap_common_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/carlike/costmap_common_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/carlike/global_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/carlike/global_costmap_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/carlike/local_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/carlike/local_costmap_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/carlike/teb_local_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/carlike/teb_local_planner_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/costmap_common_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/costmap_common_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/costmap_converter_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/costmap_converter_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/dyn_obst/costmap_converter_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/dyn_obst/costmap_converter_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/dyn_obst/global_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/dyn_obst/global_costmap_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/dyn_obst/local_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/dyn_obst/local_costmap_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/dyn_obst/teb_local_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/dyn_obst/teb_local_planner_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/global_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/global_costmap_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/local_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/local_costmap_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/teb_local_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/diff_drive/teb_local_planner_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/omnidir/costmap_common_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/omnidir/costmap_common_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/omnidir/costmap_converter_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/omnidir/costmap_converter_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/omnidir/global_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/omnidir/global_costmap_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/omnidir/local_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/omnidir/local_costmap_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/omnidir/teb_local_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/omnidir/teb_local_planner_params.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/rviz_navigation.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/rviz_navigation.rviz -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/cfg/rviz_navigation_cc.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/cfg/rviz_navigation_cc.rviz -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/launch/dyn_obst_corridor_scenario.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/launch/dyn_obst_corridor_scenario.launch -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/launch/dyn_obst_costmap_conversion.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/launch/dyn_obst_costmap_conversion.launch -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/launch/robot_carlike_in_stage.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/launch/robot_carlike_in_stage.launch -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/launch/robot_diff_drive_in_stage.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/launch/robot_diff_drive_in_stage.launch -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/launch/robot_diff_drive_in_stage_costmap_conversion.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/launch/robot_diff_drive_in_stage_costmap_conversion.launch -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/launch/robot_omnidir_in_stage.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/launch/robot_omnidir_in_stage.launch -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/maps/corridor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/maps/corridor.png -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/maps/corridor.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/maps/corridor.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/maps/empty_box.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/maps/empty_box.png -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/maps/empty_box.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/maps/empty_box.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/maps/maze.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/maps/maze.png -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/maps/maze.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/maps/maze.yaml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/package.xml -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/cmd_vel_to_ackermann_drive.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/cmd_vel_to_ackermann_drive.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/export_to_mat.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/export_to_mat.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/export_to_svg.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/export_to_svg.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/move_obstacle.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/move_obstacle.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/publish_dynamic_obstacle.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/publish_dynamic_obstacle.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/publish_ground_truth_obstacles.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/publish_ground_truth_obstacles.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/publish_test_obstacles.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/publish_test_obstacles.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/publish_viapoints.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/publish_viapoints.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/visualize_obstacle_velocity_profile.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/visualize_obstacle_velocity_profile.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/scripts/visualize_velocity_profile.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/scripts/visualize_velocity_profile.py -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/corridor.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/corridor.world -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/empty_box.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/empty_box.world -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/maze_carlike.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/maze_carlike.world -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/maze_diff_drive.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/maze_diff_drive.world -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/maze_omnidir.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/maze_omnidir.world -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/robots/carlike_robot.inc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/robots/carlike_robot.inc -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/robots/diff_drive_robot.inc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/robots/diff_drive_robot.inc -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/robots/diff_drive_robot_gps.inc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/robots/diff_drive_robot_gps.inc -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/robots/obstacle.inc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/robots/obstacle.inc -------------------------------------------------------------------------------- /custom_controllers/teb_local_planner_tutorials/stage/robots/omnidir_robot.inc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/custom_controllers/teb_local_planner_tutorials/stage/robots/omnidir_robot.inc -------------------------------------------------------------------------------- /docs/coordinates_wheels.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/docs/coordinates_wheels.jpg -------------------------------------------------------------------------------- /docs/gazebo.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/docs/gazebo.gif -------------------------------------------------------------------------------- /docs/rviz.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/docs/rviz.gif -------------------------------------------------------------------------------- /git_sync.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/git_sync.sh -------------------------------------------------------------------------------- /rbcar_common/.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | -------------------------------------------------------------------------------- /rbcar_common/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/LICENSE -------------------------------------------------------------------------------- /rbcar_common/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/README.md -------------------------------------------------------------------------------- /rbcar_common/rbcar_common/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_common/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_common/rbcar_common/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_common/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_common/rbcar_common/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_common/package.xml -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/launch/rbcar.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/launch/rbcar.rviz -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/launch/rbcar_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/launch/rbcar_rviz.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/launch/rbcar_state_robot.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/launch/rbcar_state_robot.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/meshes/bases/rbcar_chassis.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/meshes/bases/rbcar_chassis.dae -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/meshes/bases/rbcar_chassis.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/meshes/bases/rbcar_chassis.stl -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/meshes/bases/rbcar_chassis_v2.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/meshes/bases/rbcar_chassis_v2.STL -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/meshes/wheels/rbcar_wheel1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/meshes/wheels/rbcar_wheel1.dae -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/meshes/wheels/rbcar_wheel1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/meshes/wheels/rbcar_wheel1.stl -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/meshes/wheels/rbcar_wheel2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/meshes/wheels/rbcar_wheel2.dae -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/meshes/wheels/rbcar_wheel2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/meshes/wheels/rbcar_wheel2.stl -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/mybot.plugins.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/mybot.plugins.xacro -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/package.xml -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/rbcar.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/rbcar.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/robots/rbcar.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/robots/rbcar.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/urdf/bases/rbcar_base.gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/urdf/bases/rbcar_base.gazebo.xacro -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/urdf/bases/rbcar_base.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/urdf/bases/rbcar_base.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/urdf/bases/to-be-deleted/rbcar_base.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/urdf/bases/to-be-deleted/rbcar_base.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/urdf/wheels/suspension_wheel.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/urdf/wheels/suspension_wheel.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/rbcar_description/urdf/wheels/to-be-deleted/suspension_wheel.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_description/urdf/wheels/to-be-deleted/suspension_wheel.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/launch/amcl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/launch/amcl.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/launch/hector_slam.launch: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/launch/laserscan_from_pointcloud.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/launch/laserscan_from_pointcloud.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/launch/map_server.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/launch/map_server.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/launch/slam_gmapping.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/launch/slam_gmapping.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/maps/map.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/maps/map.pgm -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/maps/map.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/maps/map.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/maps/test.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/maps/test.pgm -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/maps/test.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/maps/test.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_localization/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_localization/package.xml -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/config/costmap_common_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/config/costmap_common_params.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/config/global_costmap_params_map.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/config/global_costmap_params_map.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/config/global_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/config/global_planner_params.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/config/local_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/config/local_costmap_params.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/config/move_base_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/config/move_base_params.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/config/teb_local_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/config/teb_local_planner_params.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/launch/move_base_TEB.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/launch/move_base_TEB.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/launch/move_base_mapping.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/launch/move_base_mapping.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_navigation/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_navigation/package.xml -------------------------------------------------------------------------------- /rbcar_common/rbcar_pad/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_pad/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_common/rbcar_pad/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_pad/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_common/rbcar_pad/launch/ps3.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_pad/launch/ps3.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_pad/launch/ps4.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_pad/launch/ps4.yaml -------------------------------------------------------------------------------- /rbcar_common/rbcar_pad/launch/rbcar_pad.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_pad/launch/rbcar_pad.launch -------------------------------------------------------------------------------- /rbcar_common/rbcar_pad/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_pad/package.xml -------------------------------------------------------------------------------- /rbcar_common/rbcar_pad/src/rbcar_pad.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/rbcar_pad/src/rbcar_pad.cpp -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/.gitignore: -------------------------------------------------------------------------------- 1 | # Backup files 2 | *~ 3 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/README.md -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/action/SetElevator.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/action/SetElevator.action -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/AlarmSensor.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/AlarmSensor.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Alarms.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/Alarms.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Axis.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/Axis.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/BatteryDockingStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/BatteryDockingStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/BatteryDockingStatusStamped.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/BatteryDockingStatusStamped.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/BatteryStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/BatteryStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/BatteryStatusStamped.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/BatteryStatusStamped.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/BoolArray.msg: -------------------------------------------------------------------------------- 1 | bool[] data 2 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Cartesian_Euler_pose.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/Cartesian_Euler_pose.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Data.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/Data.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/ElevatorAction.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/ElevatorAction.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/ElevatorStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/ElevatorStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Interfaces.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/Interfaces.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/InverterStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/InverterStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/LaserMode.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/LaserMode.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/LaserStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/LaserStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/MotorHeadingOffset.msg: -------------------------------------------------------------------------------- 1 | int32 motor 2 | float64 value 3 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/MotorPID.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/MotorPID.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/MotorStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/MotorStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/MotorsStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/MotorsStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/MotorsStatusDifferential.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/MotorsStatusDifferential.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/OdomCalibrationStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/OdomCalibrationStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/OdomCalibrationStatusStamped.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/OdomCalibrationStatusStamped.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/OdomManualCalibrationStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/OdomManualCalibrationStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/OdomManualCalibrationStatusStamped.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/OdomManualCalibrationStatusStamped.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Pose2DArray.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/Pose2D[] poses 2 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Pose2DStamped.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/Pose2DStamped.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/PresenceSensor.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/PresenceSensor.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/PresenceSensorArray.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/PresenceSensorArray.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/QueryAlarm.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/QueryAlarm.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Register.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/Register.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/Registers.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/Registers.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/ReturnMessage.msg: -------------------------------------------------------------------------------- 1 | bool success 2 | string message 3 | int16 code -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/RobotnikMotorsStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/RobotnikMotorsStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/SafetyModuleStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/SafetyModuleStatus.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/State.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/State.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/StringArray.msg: -------------------------------------------------------------------------------- 1 | string[] text 2 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/StringStamped.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/StringStamped.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/SubState.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/SubState.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/alarmmonitor.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/alarmmonitor.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/alarmsmonitor.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/alarmsmonitor.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/encoders.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/encoders.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/inputs_outputs.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/inputs_outputs.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/named_input_output.msg: -------------------------------------------------------------------------------- 1 | string name 2 | bool value -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/named_inputs_outputs.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/named_inputs_outputs.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/msg/ptz.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/msg/ptz.msg -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/package.xml -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/GetBool.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/GetBool.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/GetMotorsHeadingOffset.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/GetMotorsHeadingOffset.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/GetPOI.srv: -------------------------------------------------------------------------------- 1 | string name 2 | --- 3 | bool success 4 | geometry_msgs/Pose2D pose -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/GetPTZ.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/GetPTZ.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/InsertTask.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/InsertTask.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/QueryAlarms.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/QueryAlarms.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/ResetFromSubState.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/ResetFromSubState.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetBuzzer.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/SetBuzzer.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetByte.srv: -------------------------------------------------------------------------------- 1 | byte value 2 | --- 3 | bool success 4 | string message 5 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetElevator.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/SetElevator.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetEncoderTurns.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/SetEncoderTurns.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetLaserMode.srv: -------------------------------------------------------------------------------- 1 | string mode 2 | --- 3 | bool ret -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetMotorMode.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/SetMotorMode.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetMotorPID.srv: -------------------------------------------------------------------------------- 1 | MotorPID pid 2 | --- 3 | bool success 4 | string message 5 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetMotorStatus.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/SetMotorStatus.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetNamedDigitalOutput.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/SetNamedDigitalOutput.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetString.srv: -------------------------------------------------------------------------------- 1 | string data 2 | --- 3 | robotnik_msgs/ReturnMessage ret -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/SetTransform.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/SetTransform.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/ack_alarm.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/ack_alarm.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/axis_record.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/axis_record.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/enable_disable.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/enable_disable.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/get_alarms.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/get_alarms.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/get_digital_input.srv: -------------------------------------------------------------------------------- 1 | int8 input 2 | --- 3 | bool value 4 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/get_modbus_register.srv: -------------------------------------------------------------------------------- 1 | int32 address 2 | --- 3 | bool ret 4 | uint16 value 5 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/get_mode.srv: -------------------------------------------------------------------------------- 1 | --- 2 | int8 mode 3 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/home.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/home.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_CartesianEuler_pose.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/set_CartesianEuler_pose.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_analog_output.srv: -------------------------------------------------------------------------------- 1 | int8 output 2 | float32 value 3 | --- 4 | bool ret 5 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_digital_output.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/set_digital_output.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_float_value.srv: -------------------------------------------------------------------------------- 1 | float32 value 2 | --- 3 | bool ret 4 | std_msgs/String errorMessage 5 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_height.srv: -------------------------------------------------------------------------------- 1 | # New reference position (m) 2 | float32 height 3 | --- 4 | bool ret 5 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_modbus_register.srv: -------------------------------------------------------------------------------- 1 | int32 address 2 | uint16 value 3 | --- 4 | bool ret 5 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_mode.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/set_mode.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_named_digital_output.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/set_named_digital_output.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_odometry.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/set_odometry.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_msgs/srv/set_ptz.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_msgs/srv/set_ptz.srv -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/README.md -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/launch/view_sensor.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/launch/view_sensor.launch -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/launch/view_sensor.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/launch/view_sensor.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/antenna_3GO16.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/antenna_3GO16.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/antenna_3GO16.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/antenna_3GO16.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/asus_xtion_pro_live.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/asus_xtion_pro_live.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/asus_xtion_pro_live.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/asus_xtion_pro_live.png -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/axis_m5013.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/axis_m5013.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/axis_m5013.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/axis_m5013.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/axis_m5525.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/axis_m5525.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/axis_m5525.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/axis_m5525.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/axis_p5512.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/axis_p5512.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/axis_p5512.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/axis_p5512.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/axis_q8641_n1-1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/axis_q8641_n1-1.STL -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/axis_q8641_n2-1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/axis_q8641_n2-1.STL -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/benewake_ce30.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/benewake_ce30.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/camera_axis_p5514.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/camera_axis_p5514.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/camera_axis_p5514.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/camera_axis_p5514.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/camera_axis_q8641.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/camera_axis_q8641.STL -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/flir_ptu_5_base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/flir_ptu_5_base.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/flir_ptu_5_body.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/flir_ptu_5_body.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/flir_ptu_5_stand.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/flir_ptu_5_stand.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/fotonic_e.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/fotonic_e.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo.png -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo3d.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo3d.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo3d.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo3d.jpg -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo3d.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo3d.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo_urg_04lx.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo_urg_04lx.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo_urg_04lx.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo_urg_04lx.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo_ust_10lx.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo_ust_10lx.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo_ust_20lx.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo_ust_20lx.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo_utm_30lx.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo_utm_30lx.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/hokuyo_utm_30lx.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/hokuyo_utm_30lx.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/intel_d435.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/intel_d435.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/intel_d435.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/intel_d435.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/intel_r430.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/intel_r430.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/intel_r430.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/intel_r430.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/kinect.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/kinect.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/kinect.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/kinect.jpg -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/kinect.tga: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/kinect.tga -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/kinectv2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/kinectv2.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/kinectv2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/kinectv2.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/kinectv2_nobase.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/kinectv2_nobase.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/kinectv2_nobase.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/kinectv2_nobase.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/orbbec_astra.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/orbbec_astra.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/orbbec_astra.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/orbbec_astra.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/ouster1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/ouster1.STL -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/pointgrey_bumblebee2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/pointgrey_bumblebee2.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/rplidar.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/rplidar.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/rplidar_a2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/rplidar_a2.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/rplidar_a2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/rplidar_a2.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/rs_bpearl.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/rs_bpearl.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/rs_bpearl.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/rs_bpearl.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/rslidar.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/rslidar.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/rslidar.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/rslidar.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/rslidar_mems.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/rslidar_mems.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_microscan3.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_microscan3.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_microscan3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_microscan3.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_s300.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_s300.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_s300.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_s300.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_s3000.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_s3000.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_s3000.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_s3000.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_tim551.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_tim551.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_tim551.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_tim551.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_tim571.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_tim571.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/sick_tim571.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/sick_tim571.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/teraranger_tr_duo.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/teraranger_tr_duo.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/teraranger_tr_duo.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/teraranger_tr_duo.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/ueye_cp_gige.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/ueye_cp_gige.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/ueye_cp_gige.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/ueye_cp_gige.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/velodyne_vlp16.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/velodyne_vlp16.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/velodyne_vlp16.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/velodyne_vlp16.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/ydlidar_4f.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/ydlidar_4f.dae -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/ydlidar_4f.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/ydlidar_4f.png -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/zed.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/zed.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/zed2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/zed2.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/meshes/zedm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/meshes/zedm.stl -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/package.xml -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/all_sensors.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/all_sensors.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/asus_xtion_pro.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/asus_xtion_pro.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/axis.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/axis.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/axis_m5013.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/axis_m5013.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/axis_m5525.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/axis_m5525.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/axis_q8641.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/axis_q8641.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/benewake_ce30.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/benewake_ce30.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/flir_ptu_5.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/flir_ptu_5.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/fotonic_e.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/fotonic_e.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/gps.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/gps.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/gps_with_mast.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/gps_with_mast.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/hokuyo3d.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/hokuyo3d.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/hokuyo_urg04lx.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/hokuyo_urg04lx.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/hokuyo_ust10lx.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/hokuyo_ust10lx.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/hokuyo_ust20lx.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/hokuyo_ust20lx.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/hokuyo_utm30lx.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/hokuyo_utm30lx.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/imu.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/imu.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/imu_hector_plugin.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/imu_hector_plugin.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/intel_d435.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/intel_d435.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/intel_r430.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/intel_r430.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/kinect.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/kinect.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/kinectv2.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/kinectv2.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/orbbec_astra.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/orbbec_astra.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/ouster1.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/ouster1.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/pointgrey_bumblebee2.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/pointgrey_bumblebee2.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/roboteq_mgs.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/roboteq_mgs.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/rplidar.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/rplidar.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/rplidar_a2.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/rplidar_a2.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/rs_bpearl.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/rs_bpearl.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/rslidar.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/rslidar.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/rslidar_mems.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/rslidar_mems.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/rubedos_viper.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/rubedos_viper.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/sick_microscan3.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/sick_microscan3.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/sick_s300.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/sick_s300.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/sick_s3000.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/sick_s3000.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/sick_tim551.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/sick_tim551.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/sick_tim571.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/sick_tim571.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/teraranger_tr_duo.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/teraranger_tr_duo.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/ueye_cp_gige.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/ueye_cp_gige.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/velodyne_vlp16.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/velodyne_vlp16.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/ydlidar_4f.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/ydlidar_4f.urdf.xacro -------------------------------------------------------------------------------- /rbcar_common/robotnik_sensors/urdf/zed.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_common/robotnik_sensors/urdf/zed.urdf.xacro -------------------------------------------------------------------------------- /rbcar_sim/.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | -------------------------------------------------------------------------------- /rbcar_sim/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/LICENSE -------------------------------------------------------------------------------- /rbcar_sim/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/README.md -------------------------------------------------------------------------------- /rbcar_sim/rbcar_control/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_control/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_sim/rbcar_control/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_control/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_sim/rbcar_control/config/rbcar_control.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_control/config/rbcar_control.yaml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_control/config/twist_mux.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_control/config/twist_mux.yaml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_control/launch/rbcar_control.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_control/launch/rbcar_control.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_control/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_control/package.xml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/launch/rbcar.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/launch/rbcar.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/launch/rbcar_gs.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/launch/rbcar_gs.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/package.xml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/worlds/circuit.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/worlds/circuit.world -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/worlds/rbcar.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/worlds/rbcar.world -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/worlds/rbcar_gs.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/worlds/rbcar_gs.world -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/worlds/road.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/worlds/road.world -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/worlds/roadworld.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/worlds/roadworld.world -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/worlds/simple_city.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/worlds/simple_city.world -------------------------------------------------------------------------------- /rbcar_sim/rbcar_gazebo/worlds/vrc_task3_firehose_start.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_gazebo/worlds/vrc_task3_firehose_start.world -------------------------------------------------------------------------------- /rbcar_sim/rbcar_joystick/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_joystick/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_sim/rbcar_joystick/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_joystick/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_sim/rbcar_joystick/launch/ps3.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_joystick/launch/ps3.yaml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_joystick/launch/rbcar_joystick.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_joystick/launch/rbcar_joystick.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_joystick/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_joystick/package.xml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_joystick/src/rbcar_joystick.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_joystick/src/rbcar_joystick.cpp -------------------------------------------------------------------------------- /rbcar_sim/rbcar_robot_control/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_robot_control/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_sim/rbcar_robot_control/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_robot_control/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_sim/rbcar_robot_control/config/rbcar.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_robot_control/config/rbcar.yaml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_robot_control/launch/rbcar_robot_control.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_robot_control/launch/rbcar_robot_control.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_robot_control/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_robot_control/package.xml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_robot_control/src/rbcar_robot_control.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_robot_control/src/rbcar_robot_control.cpp -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/README.md -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/launch/ekf_nodes.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/launch/ekf_nodes.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/launch/my_laser_config.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/launch/my_laser_config.yaml -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/launch/my_laser_filter.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/launch/my_laser_filter.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/launch/navsat_transform_node.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/launch/navsat_transform_node.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/launch/purepursuit.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/launch/purepursuit.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/launch/purepursuit_marker.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/launch/purepursuit_marker.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/launch/rbcar_complete.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/launch/rbcar_complete.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/launch/rbcar_complete_gs.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/launch/rbcar_complete_gs.launch -------------------------------------------------------------------------------- /rbcar_sim/rbcar_sim_bringup/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_sim/rbcar_sim_bringup/package.xml -------------------------------------------------------------------------------- /rbcar_viz/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_viz/CHANGELOG.rst -------------------------------------------------------------------------------- /rbcar_viz/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_viz/CMakeLists.txt -------------------------------------------------------------------------------- /rbcar_viz/launch/view_model.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_viz/launch/view_model.launch -------------------------------------------------------------------------------- /rbcar_viz/launch/view_robot.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_viz/launch/view_robot.launch -------------------------------------------------------------------------------- /rbcar_viz/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_viz/package.xml -------------------------------------------------------------------------------- /rbcar_viz/rviz/demo_robot_mapping.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_viz/rviz/demo_robot_mapping.rviz -------------------------------------------------------------------------------- /rbcar_viz/rviz/model.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_viz/rviz/model.rviz -------------------------------------------------------------------------------- /rbcar_viz/rviz/robot.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chrissunny94/ackerman_ros_robot_gazebo_simulation/HEAD/rbcar_viz/rviz/robot.rviz --------------------------------------------------------------------------------