Add files via upload
BIN
Diagrams/hardware_wiring.pdf
Normal file
BIN
O2S CAD Assemble/o2s_full_assemble.asm
Normal file
BIN
STL & PNG Files/0.42x0.32x0.15m box.par
Normal file
BIN
STL & PNG Files/36V Lithium-ion battery 4400mAh.png
Normal file
After Width: | Height: | Size: 338 KiB |
BIN
STL & PNG Files/9X-8-ChannelTransmitterReceiver.png
Normal file
After Width: | Height: | Size: 153 KiB |
BIN
STL & PNG Files/Alu_profil_40x40.par
Normal file
BIN
STL & PNG Files/Alu_profil_40x40x165.par
Normal file
BIN
STL & PNG Files/Alu_profil_80x40.par
Normal file
BIN
STL & PNG Files/Arduino.par
Normal file
BIN
STL & PNG Files/Assembly_Robot.cfg
Normal file
6607
STL & PNG Files/Assembly_Robot.x_t
Normal file
BIN
STL & PNG Files/Battery_Pack.par
Normal file
BIN
STL & PNG Files/Bolt_M8x16.par
Normal file
BIN
STL & PNG Files/Bottom_Cover.par
Normal file
BIN
STL & PNG Files/Break_Resistor.par
Normal file
BIN
STL & PNG Files/Camera1.par
Normal file
BIN
STL & PNG Files/Camera2.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir1.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir11.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir111.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir2.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir21.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir3.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir4.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir5.par
Normal file
BIN
STL & PNG Files/Corner_40x40mm_mir6.par
Normal file
BIN
STL & PNG Files/Cover_40x40mm.par
Normal file
BIN
STL & PNG Files/Drive_Wheel.par
Normal file
BIN
STL & PNG Files/Front_hole_plate.par
Normal file
BIN
STL & PNG Files/GPIO-wires.png
Normal file
After Width: | Height: | Size: 387 KiB |
BIN
STL & PNG Files/IMU-MPU-9250.png
Normal file
After Width: | Height: | Size: 75 KiB |
BIN
STL & PNG Files/Intel Realsense D435i.png
Normal file
After Width: | Height: | Size: 63 KiB |
BIN
STL & PNG Files/MIddlebeam_240mm.par
Normal file
BIN
STL & PNG Files/MPU.par
Normal file
BIN
STL & PNG Files/Mountig_Bracket_M8.par
Normal file
BIN
STL & PNG Files/Nvidia_Jetson_Nano_B01_64GB.png
Normal file
After Width: | Height: | Size: 418 KiB |
BIN
STL & PNG Files/ODrive_V3.6_56V.png
Normal file
After Width: | Height: | Size: 334 KiB |
BIN
STL & PNG Files/Odrive.par
Normal file
BIN
STL & PNG Files/RearWheel.par
Normal file
BIN
STL & PNG Files/RearWheel_bolt.par
Normal file
BIN
STL & PNG Files/RearWheel_housing.par
Normal file
BIN
STL & PNG Files/RearWheel_mounting_plate.par
Normal file
BIN
STL & PNG Files/Screw_M6x8.par
Normal file
BIN
STL & PNG Files/Swivel caster.par
Normal file
BIN
STL & PNG Files/Top_265mm.par
Normal file
BIN
STL & PNG Files/Top_380mm.par
Normal file
BIN
STL & PNG Files/Wheelframe_160mm.par
Normal file
BIN
STL & PNG Files/lock_nut.par
Normal file
BIN
STL & PNG Files/nRF24L01+PA+LNA-module.png
Normal file
After Width: | Height: | Size: 361 KiB |
BIN
STL & PNG Files/power_bank_2400mA.png
Normal file
After Width: | Height: | Size: 67 KiB |
BIN
STL & PNG Files/rplidar_base_holder.STL
Normal file
BIN
Software Files/Arduino Sketches/arduino_sketches.tar.gz
Normal file
272
Software Files/ODrive Calibration/ODrive_calibration.py
Normal file
@ -0,0 +1,272 @@
|
||||
|
||||
|
||||
"""
|
||||
These configurations is based on Austin Owens implementation: https://github.com/AustinOwens/robodog/blob/main/odrive/configs/odrive_hoverboard_config.py
|
||||
|
||||
It was based on the hoverboard tutorial found on the Odrive Robotics website at: https://docs.odriverobotics.com/v/0.5.4/hoverboard.html
|
||||
|
||||
"""
|
||||
|
||||
import sys
|
||||
import time
|
||||
import math
|
||||
import odrive
|
||||
from odrive.enums import *
|
||||
import fibre.libfibre
|
||||
from fibre import Logger, Event
|
||||
from odrive.utils import OperationAbortedException
|
||||
|
||||
|
||||
class MotorConfig:
|
||||
"""
|
||||
Class for configuring an Odrive axis for a Hoverboard motor.
|
||||
Only works with one Odrive at a time.
|
||||
"""
|
||||
|
||||
# Hoverboard Kv
|
||||
HOVERBOARD_KV = 16.0
|
||||
|
||||
# Min/Max phase inductance of motor
|
||||
MIN_PHASE_INDUCTANCE = 0
|
||||
MAX_PHASE_INDUCTANCE = 0.001
|
||||
|
||||
# Min/Max phase resistance of motor
|
||||
MIN_PHASE_RESISTANCE = 0
|
||||
MAX_PHASE_RESISTANCE = 0.5
|
||||
|
||||
# Tolerance for encoder offset float
|
||||
ENCODER_OFFSET_FLOAT_TOLERANCE = 0.05
|
||||
|
||||
def __init__(self, axis_num):
|
||||
"""
|
||||
Initalizes MotorConfig class by finding odrive, erase its
|
||||
configuration, and grabbing specified axis object.
|
||||
|
||||
:param axis_num: Which channel/motor on the odrive your referring to.
|
||||
:type axis_num: int (0 or 1)
|
||||
"""
|
||||
|
||||
self.axis_num = axis_num
|
||||
|
||||
# Connect to Odrive
|
||||
print("Looking for ODrive...")
|
||||
self._find_odrive()
|
||||
print("Found ODrive.")
|
||||
|
||||
def _find_odrive(self):
|
||||
# connect to Odrive
|
||||
self.odrv = odrive.find_any()
|
||||
self.odrv_axis = getattr(self.odrv, "axis{}".format(self.axis_num))
|
||||
|
||||
def configure(self):
|
||||
"""
|
||||
Configures the odrive device for a hoverboard motor.
|
||||
"""
|
||||
|
||||
# Erase pre-exsisting configuration
|
||||
print("Erasing pre-exsisting configuration...")
|
||||
try:
|
||||
self.odrv.erase_configuration()
|
||||
except ChannelBrokenException:
|
||||
pass
|
||||
|
||||
self._find_odrive()
|
||||
|
||||
# Standard 6.5 inch hoverboard hub motors have 30 permanent magnet
|
||||
# poles, and thus 15 pole pairs
|
||||
self.odrv_axis.motor.config.pole_pairs = 15
|
||||
|
||||
# Hoverboard hub motors are quite high resistance compared to the hobby
|
||||
# aircraft motors, so we want to use a bit higher voltage for the motor
|
||||
# calibration, and set up the current sense gain to be more sensitive.
|
||||
# The motors are also fairly high inductance, so we need to reduce the
|
||||
# bandwidth of the current controller from the default to keep it
|
||||
# stable.
|
||||
self.odrv_axis.motor.config.resistance_calib_max_voltage = 4
|
||||
self.odrv_axis.motor.config.requested_current_range = 25
|
||||
self.odrv_axis.motor.config.current_control_bandwidth = 100
|
||||
|
||||
# Estimated KV but should be measured using the "drill test", which can
|
||||
# be found here: # https://discourse.odriverobotics.com/t/project-hoverarm/441
|
||||
self.odrv_axis.motor.config.torque_constant = 8.27 / self.HOVERBOARD_KV
|
||||
|
||||
# Hoverboard motors contain hall effect sensors instead of incremental
|
||||
# encorders
|
||||
self.odrv_axis.encoder.config.mode = ENCODER_MODE_HALL
|
||||
|
||||
# The hall feedback has 6 states for every pole pair in the motor. Since
|
||||
# we have 15 pole pairs, we set the cpr to 15*6 = 90.
|
||||
self.odrv_axis.encoder.config.cpr = 90
|
||||
|
||||
# Since hall sensors are low resolution feedback, we also bump up the
|
||||
#offset calibration displacement to get better calibration accuracy.
|
||||
self.odrv_axis.encoder.config.calib_scan_distance = 150
|
||||
|
||||
# Since the hall feedback only has 90 counts per revolution, we want to
|
||||
# reduce the velocity tracking bandwidth to get smoother velocity
|
||||
# estimates. We can also set these fairly modest gains that will be a
|
||||
# bit sloppy but shouldn’t shake your rig apart if it’s built poorly.
|
||||
# Make sure to tune the gains up when you have everything else working
|
||||
# to a stiffness that is applicable to your application.
|
||||
self.odrv_axis.encoder.config.bandwidth = 100
|
||||
self.odrv_axis.controller.config.pos_gain = 1
|
||||
self.odrv_axis.controller.config.vel_gain = 0.02 * self.odrv_axis.motor.config.torque_constant * self.odrv_axis.encoder.config.cpr
|
||||
self.odrv_axis.controller.config.vel_integrator_gain = 0.1 * self.odrv_axis.motor.config.torque_constant * self.odrv_axis.encoder.config.cpr
|
||||
self.odrv_axis.controller.config.vel_limit = 10
|
||||
|
||||
# Set in position control mode so we can control the position of the wheel
|
||||
self.odrv_axis.controller.config.control_mode = CONTROL_MODE_POSITION_CONTROL
|
||||
|
||||
# In the next step we are going to start powering the motor and so we
|
||||
# want to make sure that some of the above settings that require a
|
||||
# reboot are applied first.
|
||||
print("Saving manual configuration and rebooting...")
|
||||
self.odrv.save_configuration()
|
||||
print("Manual configuration saved.")
|
||||
try:
|
||||
self.odrv.reboot()
|
||||
except ChannelBrokenException:
|
||||
pass
|
||||
|
||||
self._find_odrive()
|
||||
|
||||
input("Make sure the motor is free to move, then press enter...")
|
||||
|
||||
print("Calibrating Odrive for hoverboard motor (you should hear a " "beep)...")
|
||||
|
||||
self.odrv_axis.requested_state = AXIS_STATE_MOTOR_CALIBRATION
|
||||
|
||||
# Wait for calibration to take place
|
||||
time.sleep(10)
|
||||
|
||||
if self.odrv_axis.motor.error != 0:
|
||||
print("Error: Odrive reported an error of {} while in the state "
|
||||
"AXIS_STATE_MOTOR_CALIBRATION. Printing out Odrive motor data for "
|
||||
"debug:\n{}".format(self.odrv_axis.motor.error,
|
||||
self.odrv_axis.motor))
|
||||
|
||||
sys.exit(1)
|
||||
|
||||
if self.odrv_axis.motor.config.phase_inductance <= self.MIN_PHASE_INDUCTANCE or \
|
||||
self.odrv_axis.motor.config.phase_inductance >= self.MAX_PHASE_INDUCTANCE:
|
||||
print("Error: After odrive motor calibration, the phase inductance "
|
||||
"is at {}, which is outside of the expected range. Either widen the "
|
||||
"boundaries of MIN_PHASE_INDUCTANCE and MAX_PHASE_INDUCTANCE (which "
|
||||
"is between {} and {} respectively) or debug/fix your setup. Printing "
|
||||
"out Odrive motor data for debug:\n{}".format(self.odrv_axis.motor.config.phase_inductance,
|
||||
self.MIN_PHASE_INDUCTANCE,
|
||||
self.MAX_PHASE_INDUCTANCE,
|
||||
self.odrv_axis.motor))
|
||||
|
||||
sys.exit(1)
|
||||
|
||||
if self.odrv_axis.motor.config.phase_resistance <= self.MIN_PHASE_RESISTANCE or \
|
||||
self.odrv_axis.motor.config.phase_resistance >= self.MAX_PHASE_RESISTANCE:
|
||||
print("Error: After odrive motor calibration, the phase resistance "
|
||||
"is at {}, which is outside of the expected range. Either raise the "
|
||||
"MAX_PHASE_RESISTANCE (which is between {} and {} respectively) or "
|
||||
"debug/fix your setup. Printing out Odrive motor data for "
|
||||
"debug:\n{}".format(self.odrv_axis.motor.config.phase_resistance,
|
||||
self.MIN_PHASE_RESISTANCE,
|
||||
self.MAX_PHASE_RESISTANCE,
|
||||
self.odrv_axis.motor))
|
||||
|
||||
sys.exit(1)
|
||||
|
||||
# If all looks good, then lets tell ODrive that saving this calibration
|
||||
# to persistent memory is OK
|
||||
self.odrv_axis.motor.config.pre_calibrated = True
|
||||
|
||||
# Check the alignment between the motor and the hall sensor. Because of
|
||||
# this step you are allowed to plug the motor phases in random order and
|
||||
# also the hall signals can be random. Just don’t change it after
|
||||
# calibration.
|
||||
print("Calibrating Odrive for encoder...")
|
||||
self.odrv_axis.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION
|
||||
|
||||
# Wait for calibration to take place
|
||||
time.sleep(30)
|
||||
|
||||
if self.odrv_axis.encoder.error != 0:
|
||||
print("Error: Odrive reported an error of {} while in the state "
|
||||
"AXIS_STATE_ENCODER_OFFSET_CALIBRATION. Printing out Odrive encoder "
|
||||
"data for debug:\n{}".format(self.odrv_axis.encoder.error,
|
||||
self.odrv_axis.encoder))
|
||||
|
||||
sys.exit(1)
|
||||
|
||||
# If offset_float isn't 0.5 within some tolerance, or its not 1.5 within
|
||||
# some tolerance, raise an error
|
||||
if not ((self.odrv_axis.encoder.config.offset_float > 0.5 - self.ENCODER_OFFSET_FLOAT_TOLERANCE and \
|
||||
self.odrv_axis.encoder.config.offset_float < 0.5 + self.ENCODER_OFFSET_FLOAT_TOLERANCE) or \
|
||||
(self.odrv_axis.encoder.config.offset_float > 1.5 - self.ENCODER_OFFSET_FLOAT_TOLERANCE and \
|
||||
self.odrv_axis.encoder.config.offset_float < 1.5 + self.ENCODER_OFFSET_FLOAT_TOLERANCE)):
|
||||
print("Error: After odrive encoder calibration, the 'offset_float' "
|
||||
"is at {}, which is outside of the expected range. 'offset_float' "
|
||||
"should be close to 0.5 or 1.5 with a tolerance of {}. Either "
|
||||
"increase the tolerance or debug/fix your setup. Printing out "
|
||||
"Odrive encoder data for debug:\n{}".format(self.odrv_axis.encoder.config.offset_float,
|
||||
self.ENCODER_OFFSET_FLOAT_TOLERANCE,
|
||||
self.odrv_axis.encoder))
|
||||
|
||||
sys.exit(1)
|
||||
|
||||
# If all looks good, then lets tell ODrive that saving this calibration
|
||||
# to persistent memory is OK
|
||||
self.odrv_axis.encoder.config.pre_calibrated = True
|
||||
|
||||
print("Saving calibration configuration and rebooting...")
|
||||
self.odrv.save_configuration()
|
||||
print("Calibration configuration saved.")
|
||||
try:
|
||||
self.odrv.reboot()
|
||||
except ChannelBrokenException:
|
||||
pass
|
||||
|
||||
self._find_odrive()
|
||||
|
||||
print("Odrive configuration finished.")
|
||||
|
||||
def mode_idle(self):
|
||||
"""
|
||||
Puts the motor in idle (i.e. can move freely).
|
||||
"""
|
||||
|
||||
self.odrv_axis.requested_state = AXIS_STATE_IDLE
|
||||
|
||||
def mode_close_loop_control(self):
|
||||
"""
|
||||
Puts the motor in closed loop control.
|
||||
"""
|
||||
|
||||
self.odrv_axis.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
|
||||
|
||||
def move_input_pos(self, angle):
|
||||
"""
|
||||
Puts the motor at a certain angle.
|
||||
|
||||
:param angle: Angle you want the motor to move.
|
||||
:type angle: int or float
|
||||
"""
|
||||
|
||||
self.odrv_axis.controller.input_pos = angle/360.0
|
||||
|
||||
if __name__ == "__main__":
|
||||
hb_motor_config = MotorConfig(axis_num = 0)
|
||||
hb_motor_config.configure()
|
||||
|
||||
print("CONDUCTING MOTOR TEST")
|
||||
print("Placing motor in close loop control. If you move motor, motor will "
|
||||
"resist you.")
|
||||
hb_motor_config.mode_close_loop_control()
|
||||
|
||||
# Go from 0 to 360 degrees in increments of 30 degrees
|
||||
for angle in range(0, 390, 30):
|
||||
print("Setting motor to {} degrees.".format(angle))
|
||||
hb_motor_config.move_input_pos(angle)
|
||||
time.sleep(5)
|
||||
|
||||
print("Placing motor in idle. If you move motor, motor will "
|
||||
"move freely")
|
||||
hb_motor_config.mode_idle()
|
||||
|
BIN
Software Files/ROS Workspace/o2s_robot.tar.gz
Normal file
46
Software Files/ROS Workspace/src/CMakeLists.txt
Normal file
@ -0,0 +1,46 @@
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
|
||||
project(o2s_robot)
|
||||
|
||||
## Compile as C++11, supported in ROS Kinetic and newer
|
||||
add_compile_options(-std=c++11)
|
||||
|
||||
## Find catkin macros and libraries
|
||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||
## is used, also find other catkin packages
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
rospy
|
||||
std_msgs
|
||||
actionlib
|
||||
move_base_msgs
|
||||
)
|
||||
|
||||
#find_package(catkin REQUIRED)
|
||||
|
||||
catkin_package()
|
||||
|
||||
include_directories(
|
||||
include
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
catkin_install_python(PROGRAMS
|
||||
# src/send_waypoints.py
|
||||
# src/odom_data.py
|
||||
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
||||
|
||||
INCLUDE_DIRECTORIES(/usr/local/lib)
|
||||
LINK_DIRECTORIES(/usr/local/lib)
|
||||
|
||||
add_executable(imuOrientToCmdVelTranslater src/imuOrientToCmdVelTranslater.cpp)
|
||||
target_link_libraries(imuOrientToCmdVelTranslater ${catkin_LIBRARIES})
|
||||
add_dependencies(imuOrientToCmdVelTranslater ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
find_package(roslaunch)
|
||||
|
||||
foreach(dir config gazebo launch maps meshes params src urdf worlds)
|
||||
install(DIRECTORY ${dir}/
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
|
||||
endforeach(dir)
|
@ -0,0 +1 @@
|
||||
controller_joint_names: ['', 'rightwheel', 'leftwheel', 'lidar', ]
|
417
Software Files/ROS Workspace/src/config/o2s_navigation.rviz
Normal file
@ -0,0 +1,417 @@
|
||||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 747
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: LaserScan
|
||||
Preferences:
|
||||
PromptSaveOnExit: true
|
||||
Toolbars:
|
||||
toolButtonStyle: 2
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 40
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
base_footprint:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camerad435i_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camerat265_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
casterwheel_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
imu_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
leftwheel_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
lidar_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
rightwheel_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
Robot Description: robot_description
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz/TF
|
||||
Enabled: true
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
base_footprint:
|
||||
Value: true
|
||||
base_link:
|
||||
Value: true
|
||||
camerad435i_link:
|
||||
Value: true
|
||||
camerat265_link:
|
||||
Value: true
|
||||
casterwheel_link:
|
||||
Value: true
|
||||
imu_link:
|
||||
Value: true
|
||||
leftwheel_link:
|
||||
Value: true
|
||||
lidar_link:
|
||||
Value: true
|
||||
map:
|
||||
Value: true
|
||||
odom:
|
||||
Value: true
|
||||
rightwheel_link:
|
||||
Value: true
|
||||
Marker Alpha: 1
|
||||
Marker Scale: 0.5
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
map:
|
||||
odom:
|
||||
base_link:
|
||||
base_footprint:
|
||||
{}
|
||||
camerad435i_link:
|
||||
{}
|
||||
camerat265_link:
|
||||
{}
|
||||
casterwheel_link:
|
||||
{}
|
||||
imu_link:
|
||||
{}
|
||||
leftwheel_link:
|
||||
{}
|
||||
lidar_link:
|
||||
{}
|
||||
rightwheel_link:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 10
|
||||
Min Value: -10
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz/LaserScan
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: Intensity
|
||||
Decay Time: 2
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Min Color: 0; 0; 0
|
||||
Name: LaserScan
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.03999999910593033
|
||||
Style: Flat Squares
|
||||
Topic: /scan
|
||||
Unreliable: false
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: true
|
||||
- Alpha: 0.699999988079071
|
||||
Class: rviz/Map
|
||||
Color Scheme: map
|
||||
Draw Behind: false
|
||||
Enabled: true
|
||||
Name: Map
|
||||
Topic: /map
|
||||
Unreliable: false
|
||||
Use Timestamp: false
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Arrow Length: 0.05000000074505806
|
||||
Axes Length: 0.30000001192092896
|
||||
Axes Radius: 0.009999999776482582
|
||||
Class: rviz/PoseArray
|
||||
Color: 31; 85; 76
|
||||
Enabled: true
|
||||
Head Length: 0.07000000029802322
|
||||
Head Radius: 0.029999999329447746
|
||||
Name: AMCL Particles
|
||||
Queue Size: 10
|
||||
Shaft Length: 0.23000000417232513
|
||||
Shaft Radius: 0.009999999776482582
|
||||
Shape: Arrow (Flat)
|
||||
Topic: /particlecloud
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Axes Length: 1
|
||||
Axes Radius: 0.10000000149011612
|
||||
Class: rviz/Pose
|
||||
Color: 255; 85; 0
|
||||
Enabled: true
|
||||
Head Length: 0.4000000059604645
|
||||
Head Radius: 0.5
|
||||
Name: Goal
|
||||
Queue Size: 10
|
||||
Shaft Length: 0.5
|
||||
Shaft Radius: 0.20000000298023224
|
||||
Shape: Arrow
|
||||
Topic: /move_base/current_goal
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Buffer Length: 1
|
||||
Class: rviz/Path
|
||||
Color: 0; 0; 255
|
||||
Enabled: true
|
||||
Head Diameter: 0.30000001192092896
|
||||
Head Length: 0.20000000298023224
|
||||
Length: 0.30000001192092896
|
||||
Line Style: Billboards
|
||||
Line Width: 0.15000000596046448
|
||||
Name: Planner Path
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Pose Color: 255; 85; 255
|
||||
Pose Style: None
|
||||
Queue Size: 10
|
||||
Radius: 0.029999999329447746
|
||||
Shaft Diameter: 0.10000000149011612
|
||||
Shaft Length: 0.10000000149011612
|
||||
Topic: /move_base/NavfnROS/plan
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/Polygon
|
||||
Color: 255; 85; 0
|
||||
Enabled: true
|
||||
Name: Footprint
|
||||
Queue Size: 10
|
||||
Topic: /move_base/local_costmap/footprint
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Alpha: 0.699999988079071
|
||||
Class: rviz/Map
|
||||
Color Scheme: costmap
|
||||
Draw Behind: false
|
||||
Enabled: true
|
||||
Name: Local Costmap
|
||||
Topic: /move_base/local_costmap/costmap
|
||||
Unreliable: false
|
||||
Use Timestamp: false
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Buffer Length: 1
|
||||
Class: rviz/Path
|
||||
Color: 0; 0; 0
|
||||
Enabled: true
|
||||
Head Diameter: 0.30000001192092896
|
||||
Head Length: 0.20000000298023224
|
||||
Length: 0.30000001192092896
|
||||
Line Style: Lines
|
||||
Line Width: 0.029999999329447746
|
||||
Name: Local Planner Path
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Pose Color: 255; 85; 255
|
||||
Pose Style: None
|
||||
Queue Size: 10
|
||||
Radius: 0.029999999329447746
|
||||
Shaft Diameter: 0.10000000149011612
|
||||
Shaft Length: 0.10000000149011612
|
||||
Topic: /move_base/DWAPlannerROS/local_plan
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Alpha: 0.699999988079071
|
||||
Class: rviz/Map
|
||||
Color Scheme: costmap
|
||||
Draw Behind: false
|
||||
Enabled: true
|
||||
Name: Global Costmap
|
||||
Topic: /move_base/global_costmap/costmap
|
||||
Unreliable: false
|
||||
Use Timestamp: false
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Buffer Length: 1
|
||||
Class: rviz/Path
|
||||
Color: 255; 255; 0
|
||||
Enabled: true
|
||||
Head Diameter: 0.30000001192092896
|
||||
Head Length: 0.20000000298023224
|
||||
Length: 0.30000001192092896
|
||||
Line Style: Lines
|
||||
Line Width: 0.029999999329447746
|
||||
Name: Global Planner Path
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Pose Color: 255; 85; 255
|
||||
Pose Style: None
|
||||
Queue Size: 10
|
||||
Radius: 0.029999999329447746
|
||||
Shaft Diameter: 0.10000000149011612
|
||||
Shaft Length: 0.10000000149011612
|
||||
Topic: /move_base/DWAPlannerROS/global_plan
|
||||
Unreliable: false
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/PointStamped
|
||||
Color: 204; 41; 204
|
||||
Enabled: true
|
||||
History Length: 1
|
||||
Name: PointStamped
|
||||
Queue Size: 10
|
||||
Radius: 0.20000000298023224
|
||||
Topic: /clicked_point
|
||||
Unreliable: false
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Default Light: true
|
||||
Fixed Frame: map
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Theta std deviation: 0.2617993950843811
|
||||
Topic: /initialpose
|
||||
X std deviation: 0.5
|
||||
Y std deviation: 0.5
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/XYOrbit
|
||||
Distance: 22.512256622314453
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Field of View: 0.7853981852531433
|
||||
Focal Point:
|
||||
X: 1.7694363594055176
|
||||
Y: -13.823583602905273
|
||||
Z: -1.430511474609375e-06
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 1.5147963762283325
|
||||
Target Frame: <Fixed Frame>
|
||||
Yaw: 4.70358943939209
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 1044
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd00000004000000000000019600000374fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000374000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000374fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b00000374000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000078000000044fc0100000002fb0000000800540069006d00650100000000000007800000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000004cf0000037400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1920
|
||||
X: 1920
|
||||
Y: 0
|
229
Software Files/ROS Workspace/src/config/rviz_config.rviz
Normal file
@ -0,0 +1,229 @@
|
||||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 753
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: LaserScan
|
||||
Preferences:
|
||||
PromptSaveOnExit: true
|
||||
Toolbars:
|
||||
toolButtonStyle: 2
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 10
|
||||
Min Value: -10
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz/LaserScan
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: Intensity
|
||||
Decay Time: 0
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Min Color: 0; 0; 0
|
||||
Name: LaserScan
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.029999999329447746
|
||||
Style: Flat Squares
|
||||
Topic: /scan
|
||||
Unreliable: false
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camerad435i_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
camerat265_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
casterwheel_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
imu_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
leftwheel_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
lidar_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
rightwheel_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
Robot Description: robot_description
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Alpha: 0.699999988079071
|
||||
Class: rviz/Map
|
||||
Color Scheme: map
|
||||
Draw Behind: false
|
||||
Enabled: true
|
||||
Name: Map
|
||||
Topic: map
|
||||
Unreliable: false
|
||||
Use Timestamp: false
|
||||
Value: true
|
||||
- Class: rviz/TF
|
||||
Enabled: false
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
Marker Alpha: 1
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: false
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Default Light: true
|
||||
Fixed Frame: odom
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Theta std deviation: 0.2617993950843811
|
||||
Topic: /initialpose
|
||||
X std deviation: 0.5
|
||||
Y std deviation: 0.5
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 6.662227630615234
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Field of View: 0.7853981852531433
|
||||
Focal Point:
|
||||
X: 12.082286834716797
|
||||
Y: -9.459827423095703
|
||||
Z: 3.169853448867798
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.10539796203374863
|
||||
Target Frame: <Fixed Frame>
|
||||
Yaw: 0.9303956627845764
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 1044
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001560000037afc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b0000037a000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000037afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b0000037a000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000024400fffffffb0000000800540069006d006501000000000000045000000000000000000000050f0000037a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1920
|
||||
X: 1920
|
||||
Y: 0
|
413
Software Files/ROS Workspace/src/export.log
Normal file
27
Software Files/ROS Workspace/src/gazebo/o2s.trans
Normal file
@ -0,0 +1,27 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="o2s_robot" xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<!-- ****************** o2s base transmission******************* -->
|
||||
<transmission name="rightwheel_joint_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="rightwheel_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="rightwheel_joint_actr">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="leftwheel_joint_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="leftwheel_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="leftwheel_joint_actr">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
</robot>
|
@ -0,0 +1,40 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="o2s_robot" xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<xacro:property name="base_link_color" value="Gazebo/White" />
|
||||
<xacro:property name="camerad435i_link_color" value="Gazebo/White" />
|
||||
<xacro:property name="camerat265_link_color" value="Gazebo/White" />
|
||||
<xacro:property name="lidar_color" value="Gazebo/LightBlueLaser" />
|
||||
<xacro:property name="imu_link_color" value="Gazebo/Black" />
|
||||
<xacro:property name="wheels_link_color" value="Gazebo/Black" />
|
||||
<xacro:property name="casterwheel_link_color" value="Gazebo/Blue" />
|
||||
|
||||
<gazebo reference="base_link">
|
||||
<material>${base_link_color}</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="camerad435i_link">
|
||||
<material>${camerad435i_link_color}</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<material>${imu_link_color}</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="rightwheel_link">
|
||||
<material>${wheels_link_color}</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="leftwheel_link">
|
||||
<material>${wheels_link_color}</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="casterwheel_link">
|
||||
<material>${casterwheel_link_color}</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="lidar_link">
|
||||
<material>${lidar_color}</material>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
@ -0,0 +1,58 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="o2s_robot" xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<xacro:property name="standard_friction" value="1.0" />
|
||||
<xacro:property name="caster_friction" value="0.01" />
|
||||
<xacro:property name="wheels_friction" value="1000.0" />
|
||||
|
||||
<gazebo reference="base_link">
|
||||
<mu1>${standard_friction}</mu1>
|
||||
<mu2>${standard_friction}</mu2>
|
||||
<selfCollide>true</selfCollide>
|
||||
<gravity>true</gravity>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="rightwheel_link">
|
||||
<mu1>${wheels_friction}</mu1>
|
||||
<mu2>${wheels_friction}</mu2>
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="leftwheel_link">
|
||||
<mu1>${wheels_friction}</mu1>
|
||||
<mu2>${wheels_friction}</mu2>
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="casterwheel_link">
|
||||
<mu1>${caster_friction}</mu1>
|
||||
<mu2>${caster_friction}</mu2>
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="lidar_link">
|
||||
<mu1>${standard_friction}</mu1>
|
||||
<mu2>${standard_friction}</mu2>
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="camerad435i_link">
|
||||
<mu1>${standard_friction}</mu1>
|
||||
<mu2>${standard_friction}</mu2>
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="camerat265_link">
|
||||
<mu1>${standard_friction}</mu1>
|
||||
<mu2>${standard_friction}</mu2>
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<mu1>${standard_friction}</mu1>
|
||||
<mu2>${standard_friction}</mu2>
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
@ -0,0 +1,136 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="o2s_robot" xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<!-- *********** O2S ROS Control ***************** -->
|
||||
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_control.so" name="control"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- ************ o2s differential drive plugin ************* -->
|
||||
|
||||
<gazebo>
|
||||
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
|
||||
<updateRate>20</updateRate>
|
||||
<leftJoint>leftwheel_joint</leftJoint>
|
||||
<rightJoint>rightwheel_joint</rightJoint>
|
||||
<wheelSeparation>0.30</wheelSeparation>
|
||||
<wheelDiameter>0.1610</wheelDiameter>
|
||||
<wheelAcceleration>1.0</wheelAcceleration>
|
||||
<wheelTorque>20</wheelTorque>
|
||||
<commandTopic>cmd_vel</commandTopic>
|
||||
<odometryTopic>odom</odometryTopic>
|
||||
<odometryFrame>odom</odometryFrame>
|
||||
<robotBaseFrame>base_link</robotBaseFrame>
|
||||
<odometrySource>1</odometrySource>
|
||||
<publishWheelTF>false</publishWheelTF>
|
||||
<publishOdom>true</publishOdom>
|
||||
<publishTf>1</publishTf>
|
||||
<publishOdomTF>true</publishOdomTF>
|
||||
<publishWheelJointState>true</publishWheelJointState>
|
||||
<legacyMode>false</legacyMode>
|
||||
<alwaysOn>true</alwaysOn>
|
||||
<odometrySource>world</odometrySource>
|
||||
<rosDebugLevel>Debug</rosDebugLevel>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- *********** o2s lidar sensor plugin ************* -->
|
||||
|
||||
<gazebo reference="lidar_link">
|
||||
<sensor type="ray" name="rplidar_a2">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>true</visualize>
|
||||
<update_rate>10</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>720</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-2.98451</min_angle>
|
||||
<max_angle>2.98451</max_angle>
|
||||
</horizontal>
|
||||
</scan>
|
||||
<range>
|
||||
<min>0.15</min>
|
||||
<max>16.0</max>
|
||||
<resolution>0.01</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.01</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
|
||||
<topicName>/scan</topicName>
|
||||
<frameName>lidar_link</frameName>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- ************* IMU sensor plugin ***************** -->
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<gravity>true</gravity>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>true</always_on>
|
||||
<update_rate>10</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>__default_topic__</topic>
|
||||
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
||||
<topicName>imu</topicName>
|
||||
<bodyName>imu_link</bodyName>
|
||||
<updateRateHZ>10.0</updateRateHZ>
|
||||
<gaussianNoise>0.0</gaussianNoise>
|
||||
<xyzOffset>0 0 0</xyzOffset>
|
||||
<rpyOffset>0 0 0</rpyOffset>
|
||||
<frameName>imu_link</frameName>
|
||||
<initialOrientationAsReference>false</initialOrientationAsReference>
|
||||
</plugin>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- ********************* Camera sensor plugin ******************* -->
|
||||
|
||||
<gazebo reference="camerad435i_link">
|
||||
<sensor type="camera" name="camera1">
|
||||
<update_rate>30.0</update_rate>
|
||||
<camera name="head">
|
||||
<horizontal_fov>1.3962634</horizontal_fov>
|
||||
<image>
|
||||
<width>640</width>
|
||||
<height>320</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.02</near>
|
||||
<far>300</far>
|
||||
</clip>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.007</stddev>
|
||||
</noise>
|
||||
</camera>
|
||||
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
||||
<alwaysOn>true</alwaysOn>
|
||||
<updateRate>0.0</updateRate>
|
||||
<cameraName>o2s/camera</cameraName>
|
||||
<imageTopicName>image_raw</imageTopicName>
|
||||
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
|
||||
<frameName>camera_link</frameName>
|
||||
<hackBaseline>0.07</hackBaseline>
|
||||
<distortionK1>0.0</distortionK1>
|
||||
<distortionK2>0.0</distortionK2>
|
||||
<distortionK3>0.0</distortionK3>
|
||||
<distortionT1>0.0</distortionT1>
|
||||
<distortionT2>0.0</distortionT2>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
||||
|
||||
|
55
Software Files/ROS Workspace/src/launch/amcl.launch
Normal file
@ -0,0 +1,55 @@
|
||||
<?xml version = "1.0"?>
|
||||
<launch>
|
||||
<!-- Argument -->
|
||||
<arg name="scan_topic" default="scan"/>
|
||||
|
||||
<!--******* Initial pose mean, used to initialize filter with Gaussian distribution ********** -->
|
||||
<!--
|
||||
<arg name="initial_pose_x" default="0.0"/>
|
||||
<arg name="initial_pose_y" default="0.0"/>
|
||||
<arg name="initial_pose_a" default="0.0"/>
|
||||
-->
|
||||
<arg name="initial_pose_x" value="0.67"/>
|
||||
<arg name="initial_pose_y" value="-13.49"/>
|
||||
<arg name="initial_pose_a" value="0.0"/>
|
||||
|
||||
<!-- ********** AMCL algorithm *********** -->
|
||||
<node pkg="amcl" type="amcl" name="amcl">
|
||||
|
||||
<param name="min_particles" value="500"/>
|
||||
<param name="max_particles" value="3000"/>
|
||||
<param name="kld_err" value="0.02"/>
|
||||
<param name="update_min_d" value="0.20"/>
|
||||
<param name="update_min_a" value="0.20"/>
|
||||
<param name="resample_interval" value="1"/>
|
||||
<param name="transform_tolerance" value="0.5"/>
|
||||
<param name="recovery_alpha_slow" value="0.00"/>
|
||||
<param name="recovery_alpha_fast" value="0.00"/>
|
||||
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
|
||||
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
|
||||
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
|
||||
<param name="gui_publish_rate" value="50.0"/>
|
||||
|
||||
<remap from="scan" to="$(arg scan_topic)"/>
|
||||
<param name="laser_max_range" value="3.5"/>
|
||||
<param name="laser_max_beams" value="180"/>
|
||||
<param name="laser_z_hit" value="0.5"/>
|
||||
<param name="laser_z_short" value="0.05"/>
|
||||
<param name="laser_z_max" value="0.05"/>
|
||||
<param name="laser_z_rand" value="0.5"/>
|
||||
<param name="laser_sigma_hit" value="0.2"/>
|
||||
<param name="laser_lambda_short" value="0.1"/>
|
||||
<param name="laser_likelihood_max_dist" value="2.0"/>
|
||||
<param name="laser_model_type" value="likelihood_field"/>
|
||||
|
||||
<param name="odom_model_type" value="diff"/>
|
||||
<param name="odom_alpha1" value="0.1"/>
|
||||
<param name="odom_alpha2" value="0.1"/>
|
||||
<param name="odom_alpha3" value="0.1"/>
|
||||
<param name="odom_alpha4" value="0.1"/>
|
||||
<param name="odom_frame_id" value="odom"/>
|
||||
<param name="base_frame_id" value="base_footprint"/>
|
||||
|
||||
</node>
|
||||
</launch>
|
||||
|
23
Software Files/ROS Workspace/src/launch/gazebo.launch
Normal file
@ -0,0 +1,23 @@
|
||||
<?xml version="1.0" ?>
|
||||
|
||||
<!-- *********** This launch file launches the o2s in an empty Gazebo world *********** -->
|
||||
<launch>
|
||||
<include
|
||||
file="$(find gazebo_ros)/launch/empty_world.launch" />
|
||||
<node
|
||||
name="tf_footprint_base"
|
||||
pkg="tf"
|
||||
type="static_transform_publisher"
|
||||
args="0 0 0 0 0 0 base_link base_footprint 40" />
|
||||
<node
|
||||
name="spawn_model"
|
||||
pkg="gazebo_ros"
|
||||
type="spawn_model"
|
||||
args="-file $(find o2s_robot)/urdf/o2s_robot.xacro -urdf -model o2s_robot"
|
||||
output="screen" />
|
||||
<!--<node
|
||||
name="fake_joint_calibration"
|
||||
pkg="rostopic"
|
||||
type="rostopic"
|
||||
args="pub /calibrated std_msgs/Bool true" /> -->
|
||||
</launch>
|
24
Software Files/ROS Workspace/src/launch/move_base.launch
Normal file
@ -0,0 +1,24 @@
|
||||
<?xml version = "1.0"?>
|
||||
|
||||
<!-- ********** This move_base node provides a ROS interface for configuring and interacting with the navigation stack on o2s ********** -->
|
||||
<launch>
|
||||
<!-- Argument -->
|
||||
<arg name="cmd_vel_topic" default="/cmd_vel" />
|
||||
<arg name="odom_topic" default="odom" />
|
||||
<arg name="move_forward_only" default="false"/>
|
||||
|
||||
<!-- move_base -->
|
||||
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
|
||||
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
|
||||
<rosparam file="$(find o2s_robot)/params/costmap_common_params.yaml" command="load" ns="global_costmap" />
|
||||
<rosparam file="$(find o2s_robot)/params/costmap_common_params.yaml" command="load" ns="local_costmap" />
|
||||
<rosparam file="$(find o2s_robot)/params/local_costmap_params.yaml" command="load" />
|
||||
<rosparam file="$(find o2s_robot)/params/global_costmap_params.yaml" command="load" />
|
||||
<rosparam file="$(find o2s_robot)/params/move_base_params.yaml" command="load" />
|
||||
<rosparam file="$(find o2s_robot)/params/dwa_local_planner_params.yaml" command="load" />
|
||||
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
|
||||
<remap from="odom" to="$(arg odom_topic)"/>
|
||||
<param name="DWAPlannerROS/min_vel_x" value="0.0" if="$(arg move_forward_only)" />
|
||||
|
||||
</node>
|
||||
</launch>
|
27
Software Files/ROS Workspace/src/launch/o2s_bringup.launch
Normal file
@ -0,0 +1,27 @@
|
||||
<?xml version = "1.0"?>
|
||||
<launch>
|
||||
<param name ="/use_sim_time" value="true"/> <!-- set to false if on real-world -->
|
||||
|
||||
<arg name="gui" default="True" />
|
||||
<param name="use_gui" value="$(arg gui)"/>
|
||||
<param name="robot_description" command="cat $(find o2s_robot)/urdf/o2s_robot.xacro" />
|
||||
|
||||
<!-- ***** Setting up the transformation configuration (the relationships between the coordinate frames ***** -->
|
||||
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/>
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
||||
|
||||
<!--
|
||||
<node pkg ="tf" type="static_transform_publisher" name="odom_to_base_link" args="0.0 0.0 0.0 0.0 0.0 0.0 /odom /base_link 40"/>
|
||||
<node pkg ="tf" type="static_transform_publisher" name="base_link_to_laser" args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /lidar_link 40"/>
|
||||
-->
|
||||
|
||||
<!-- ***** Launch the rosserial python node ***** -->
|
||||
<node name="serial_node" pkg="rosserial_python" type="serial_node.py">
|
||||
<param name="port" value="/dev/ttyACM0"/>
|
||||
<param name="baud" value="115200"/>
|
||||
</node>
|
||||
|
||||
<!-- ***** Launch the RPlidar node ***** -->
|
||||
<include file="$(find rplidar_ros)/launch/rplidar.launch" />
|
||||
|
||||
</launch>
|
30
Software Files/ROS Workspace/src/launch/o2s_house.launch
Normal file
@ -0,0 +1,30 @@
|
||||
<?xml version="1.0" ?>
|
||||
|
||||
<launch>
|
||||
|
||||
<param command="$(find xacro)/xacro $(find o2s_robot)/urdf/o2s_robot.xacro" name="robot_description"/>
|
||||
<!--
|
||||
<arg name="x" default="0.0" />
|
||||
<arg name="y" default="0.0" />
|
||||
<arg name="z" default="0.0" />
|
||||
-->
|
||||
<arg name="x" value="0.67" />
|
||||
<arg name="y" value="-13.49" />
|
||||
<arg name="z" value="0.0" />
|
||||
|
||||
<node args="-param robot_description -urdf -x $(arg x) -y $(arg y) -z $(arg z) -model o2s_robot" name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"/>
|
||||
|
||||
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/>
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
||||
|
||||
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="paused" value="false"/>
|
||||
<arg name="use_sim_time" value="true"/> <!-- set to false if on real-world -->
|
||||
<arg name="gui" value="true"/>
|
||||
<arg name="headless" value="false"/>
|
||||
<arg name="debug" value="false"/>
|
||||
<arg name="world_name" value="$(find o2s_robot)/worlds/laboratory_world.world"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
@ -0,0 +1,29 @@
|
||||
<?xml version = "1.0"?>
|
||||
<launch>
|
||||
<!--*********** Arguments ************ -->
|
||||
|
||||
<arg name="open_rviz" default="true"/>
|
||||
<arg name="move_forward_only" default="false"/>
|
||||
|
||||
<!--*********** Map server ***********-->
|
||||
|
||||
<node pkg="map_server" name="map_server" type="map_server" args="$(find o2s_robot)/maps/o2s_lab_map.yaml"/>
|
||||
|
||||
<!--*********** AMCL algorithm ***********-->
|
||||
|
||||
<include file="$(find o2s_robot)/launch/amcl.launch"/>
|
||||
|
||||
<!--*********** move_base ***********-->
|
||||
|
||||
<include file="$(find o2s_robot)/launch/move_base.launch">
|
||||
<arg name="move_forward_only" value="$(arg move_forward_only)"/>
|
||||
</include>
|
||||
|
||||
<!--*********** rviz ***********-->
|
||||
|
||||
<group if="$(arg open_rviz)">
|
||||
<node pkg="rviz" type="rviz" name="rviz" required="true"
|
||||
args="-d $(find o2s_robot)/config/o2s_navigation.rviz"/>
|
||||
</group>
|
||||
|
||||
</launch>
|
24
Software Files/ROS Workspace/src/launch/o2s_rviz.launch
Normal file
@ -0,0 +1,24 @@
|
||||
<?xml version="1.0" ?>
|
||||
|
||||
<!--*********** Visualise o2s in Rviz *********** -->
|
||||
<launch>
|
||||
<arg
|
||||
name="model" />
|
||||
<param
|
||||
name="robot_description"
|
||||
textfile="$(find o2s_robot)/urdf/o2s_robot.xacro" />
|
||||
<!-- <node
|
||||
name="joint_state_publisher_gui"
|
||||
pkg="joint_state_publisher_gui"
|
||||
type="joint_state_publisher_gui" />
|
||||
<node
|
||||
name="robot_state_publisher"
|
||||
pkg="robot_state_publisher"
|
||||
type="robot_state_publisher" /> -->
|
||||
<node
|
||||
name="rviz"
|
||||
pkg="rviz"
|
||||
type="rviz"
|
||||
args="-d $(find o2s_robot)/config/rviz_config.rviz" />
|
||||
</launch>
|
||||
|
@ -0,0 +1,7 @@
|
||||
image: hector_laboratory_map.pgm
|
||||
resolution: 0.050000
|
||||
origin: [-51.224998, -51.224998, 0.000000]
|
||||
negate: 0
|
||||
occupied_thresh: 0.65
|
||||
free_thresh: 0.196
|
||||
|
5
Software Files/ROS Workspace/src/maps/laboratory_map.pgm
Normal file
@ -0,0 +1,7 @@
|
||||
image: laboratory_map.pgm
|
||||
resolution: 0.050000
|
||||
origin: [-100.000000, -100.000000, 0.000000]
|
||||
negate: 0
|
||||
occupied_thresh: 0.65
|
||||
free_thresh: 0.196
|
||||
|
5
Software Files/ROS Workspace/src/maps/o2s_lab_map.pgm
Normal file
7
Software Files/ROS Workspace/src/maps/o2s_lab_map.yaml
Normal file
@ -0,0 +1,7 @@
|
||||
image: o2s_lab_map.pgm
|
||||
resolution: 0.050000
|
||||
origin: [-51.224998, -51.224998, 0.000000]
|
||||
negate: 0
|
||||
occupied_thresh: 0.65
|
||||
free_thresh: 0.196
|
||||
|
BIN
Software Files/ROS Workspace/src/meshes/base_link.STL
Normal file
BIN
Software Files/ROS Workspace/src/meshes/camerad435i.STL
Normal file
BIN
Software Files/ROS Workspace/src/meshes/camerat265.STL
Normal file
BIN
Software Files/ROS Workspace/src/meshes/casterwheel.STL
Normal file
BIN
Software Files/ROS Workspace/src/meshes/imu.STL
Normal file
BIN
Software Files/ROS Workspace/src/meshes/leftwheel.STL
Normal file
BIN
Software Files/ROS Workspace/src/meshes/lidar.STL
Normal file
BIN
Software Files/ROS Workspace/src/meshes/rightwheel.STL
Normal file
45
Software Files/ROS Workspace/src/package.xml
Normal file
@ -0,0 +1,45 @@
|
||||
<package format="2">
|
||||
<name>o2s_robot</name>
|
||||
<version>1.0.0</version>
|
||||
<description>
|
||||
<p>URDF Description package for o2s_assem.SLDASM</p>
|
||||
<p>This package contains configuration data, 3D models and launch files
|
||||
for o2s_robot robot</p>
|
||||
</description>
|
||||
<author>TODO</author>
|
||||
<maintainer email="TODO@email.com" />
|
||||
<license>BSD</license>
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>rospy</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_depend>actionlib</build_depend>
|
||||
<build_depend>actionlib_msgs</build_depend>
|
||||
<build_depend>move_base_msgs</build_depend>
|
||||
<build_depend>sensor_msgs</build_depend>
|
||||
<build_depend>roslint</build_depend>
|
||||
<build_depend>std_srvs</build_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<build_export_depend>rospy</build_export_depend>
|
||||
<build_export_depend>std_msgs</build_export_depend>
|
||||
<build_export_depend>actionlib</build_export_depend>
|
||||
<build_export_depend>move_base_msgs</build_export_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>rospy</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
<exec_depend>actionlib</exec_depend>
|
||||
<exec_depend>actionlib_msgs</exec_depend>
|
||||
<exec_depend>move_base_msgs</exec_depend>
|
||||
<exec_depend>imu_filter_madgwick</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>sensor_msgs</exec_depend>
|
||||
<exec_depend>std_srvs</exec_depend>
|
||||
<depend>roslaunch</depend>
|
||||
<depend>robot_state_publisher</depend>
|
||||
<depend>rviz</depend>
|
||||
<depend>joint_state_publisher_gui</depend>
|
||||
<depend>gazebo</depend>
|
||||
<export>
|
||||
<architecture_independent />
|
||||
</export>
|
||||
</package>
|
@ -0,0 +1,44 @@
|
||||
TrajectoryPlannerROS:
|
||||
|
||||
# Robot Configuration Parameters
|
||||
max_vel_x: 0.3
|
||||
min_vel_x: 0.1
|
||||
|
||||
max_vel_theta: 1.0
|
||||
min_vel_theta: -1.0
|
||||
min_in_place_vel_theta: 0.4
|
||||
|
||||
acc_lim_x: 2.5
|
||||
acc_lim_y: 0.0
|
||||
acc_lim_theta: 3.2
|
||||
|
||||
# Goal Tolerance Parameters
|
||||
xy_goal_tolerance: 0.15
|
||||
yaw_goal_tolerance: 0.1
|
||||
latch_xy_goal_tolerance: false
|
||||
|
||||
# Forward Simulation Parameters
|
||||
sim_time: 3.0
|
||||
vx_samples: 6
|
||||
vtheta_samples: 20
|
||||
sim_granularity: 0.05
|
||||
|
||||
# Trajectory Scoring Parameters
|
||||
meter_scoring: true
|
||||
pdist_scale: 0.6
|
||||
gdist_scale: 0.8
|
||||
occdist_scale: 0.01
|
||||
heading_lookahead: 0.325
|
||||
# dwa: true
|
||||
|
||||
# Oscillation Prevention Parameters
|
||||
oscillation_reset_dist: 0.05
|
||||
|
||||
# Differential-drive robot configuration
|
||||
holonomic_robot: false
|
||||
max_vel_y: 0.0
|
||||
min_vel_y: 0.0
|
||||
acc_lim_y: 0.0
|
||||
vy_samples: 1
|
||||
|
||||
|
16
Software Files/ROS Workspace/src/params/controller.yaml
Normal file
@ -0,0 +1,16 @@
|
||||
o2s_robot_controller:
|
||||
# Publish all joint states -----------------------------------
|
||||
joint_state_controller:
|
||||
type: joint_state_controller/JointStateController
|
||||
publish_rate: 50
|
||||
|
||||
# Position Controllers --------------------------------------
|
||||
rightwheel_joint_position_controller:
|
||||
type: effort_controllers/JointPositionController
|
||||
joint: rightwheel_joint
|
||||
pid: {p: 100.0, i: 0.01, d: 10.0}
|
||||
leftwheel_joint_position_controller:
|
||||
type: effort_controllers/JointPositionController
|
||||
joint: leftwheel_joint
|
||||
pid: {p: 100.0, i: 0.01, d: 10.0}
|
||||
|
@ -0,0 +1,26 @@
|
||||
footprint: [[-0.20, -0.20], [-0.20, 0.20], [0.20, 0.20], [0.20, -0.20]]
|
||||
|
||||
transform_tolerance: 0.5
|
||||
map_type: costmap
|
||||
|
||||
#Obstacle marking parameters
|
||||
obstacle_layer:
|
||||
enabled: true
|
||||
obstacle_range: 2.5
|
||||
raytrace_range: 3.5
|
||||
inflation_radius: 0.5
|
||||
track_unknown_space: false
|
||||
combination_method: 1
|
||||
subscribe_to_updates: true
|
||||
observation_sources: laser_scan_sensor
|
||||
laser_scan_sensor: {data_type: LaserScan, topic: scan, marking: true, clearing: true}
|
||||
|
||||
#Cost function parameters
|
||||
inflation_layer:
|
||||
enabled: true
|
||||
cost_scaling_factor: 5.0
|
||||
inflation_radius: 0.5
|
||||
|
||||
static_layer:
|
||||
enabled: true
|
||||
map_topic: "map"
|
@ -0,0 +1,50 @@
|
||||
DWAPlannerROS:
|
||||
|
||||
# Robot Configuration Parameters
|
||||
max_vel_x: 0.5
|
||||
min_vel_x: 0.0
|
||||
|
||||
max_vel_y: 0.0
|
||||
min_vel_y: 0.0
|
||||
|
||||
# The velocity when robot is moving in a straight line
|
||||
max_vel_trans: 0.5
|
||||
min_vel_trans: 0.11
|
||||
trans_stopped_vel: 0.1
|
||||
|
||||
max_vel_theta: 2.75
|
||||
min_vel_theta: 1.37
|
||||
|
||||
acc_lim_x: 2.5
|
||||
acc_lim_y: 0.0
|
||||
acc_lim_theta: 3.2
|
||||
|
||||
# Goal Tolerance Parametes
|
||||
xy_goal_tolerance: 0.15
|
||||
yaw_goal_tolerance: 0.3
|
||||
latch_xy_goal_tolerance: false
|
||||
|
||||
# Forward Simulation Parameters
|
||||
sim_time: 1.5
|
||||
vx_samples: 6
|
||||
vy_samples: 1
|
||||
vth_samples: 20
|
||||
controller_frequency: 10.0
|
||||
|
||||
# Trajectory Scoring Parameters
|
||||
path_distance_bias: 64.0
|
||||
goal_distance_bias: 24
|
||||
occdist_scale: 0.5
|
||||
forward_point_distance: 0.325
|
||||
stop_time_buffer: 0.2
|
||||
scaling_speed: 0.25
|
||||
max_scaling_factor: 0.2
|
||||
|
||||
# Oscillation Prevention Parameters
|
||||
oscillation_reset_dist: 0.05
|
||||
|
||||
# Debugging
|
||||
publish_traj_pc : true
|
||||
publish_cost_grid_pc: true
|
||||
|
||||
|
@ -0,0 +1,15 @@
|
||||
global_costmap:
|
||||
global_frame: map
|
||||
|
||||
robot_base_frame: base_link
|
||||
update_frequency: 5.0
|
||||
publish_frequency: 5.0
|
||||
static_map: false
|
||||
resolution: 0.025
|
||||
|
||||
transform_tolerance: 0.5
|
||||
plugins:
|
||||
- {name: static_layer, type: "costmap_2d::StaticLayer"}
|
||||
- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
|
||||
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
|
||||
|
@ -0,0 +1,20 @@
|
||||
local_costmap:
|
||||
global_frame: map
|
||||
|
||||
robot_base_frame: base_link
|
||||
update_frequency: 5.0
|
||||
publish_frequency: 5.0
|
||||
static_map: false
|
||||
rolling_window: true
|
||||
width: 8
|
||||
height: 8
|
||||
resolution: 0.025
|
||||
inflation_radius: 0.5
|
||||
transform_tolerance: 0.5
|
||||
|
||||
plugins:
|
||||
- {name: static_layer, type: "costmap_2d::StaticLayer"}
|
||||
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
|
||||
|
||||
|
||||
|
@ -0,0 +1,11 @@
|
||||
shutdown_costmaps: false
|
||||
controller_frequency: 20.0
|
||||
planner_patience: 5.0
|
||||
controller_patience: 15.0
|
||||
conservative_reset_dist: 3.0
|
||||
recovery_behavior_enabled: true
|
||||
clearing_rotation_allowed: true
|
||||
planner_frequency: 5.0
|
||||
oscillation_timeout: 10.0
|
||||
oscillation_distance: 0.2
|
||||
|
@ -0,0 +1,89 @@
|
||||
/*
|
||||
This code computes the linear velocity and rotation speed of o2s based on the orientation of the IMU sensor (P19). At first step, the orientation is received from the "imu/data" topic in the form of a quaternion. Then, in the second step, the quaternions are used to calculate the angular rotation (the roll, pitch and yaw angles) of the sensor from the neutral position. Based on the roll and pitch values the command velocity of the robot is calculated and published to the cmd_vel topic of ROS.
|
||||
|
||||
The code for computation of the roll, pitch and yaw values from the quaternion are based on the code from the following website: https://blog.karatos.in/a?ID=00750-4151b77d-39bf-4067-a2e2-9543486eabc4
|
||||
For more information about writing a publisher/subscriber nodes, visit: http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29
|
||||
*/
|
||||
|
||||
#include "ros/ros.h"
|
||||
#include <sensor_msgs/Imu.h>
|
||||
#include <geometry_msgs/Twist.h>
|
||||
#include "std_msgs/String.h"
|
||||
#include <tf/tf.h>
|
||||
#include <sstream>
|
||||
|
||||
//defining the variables
|
||||
double linearVelFactor = 0.3;
|
||||
double rotSpeedFactor = 1.5;
|
||||
|
||||
double roll, pitch, yaw;
|
||||
double linearVelocity, angularRotationSpeed;
|
||||
float pi = 3.1415926535897932384626433832795;
|
||||
|
||||
geometry_msgs::Twist cmd_vel_msg;
|
||||
ros::Publisher cmd_vel_Publisher;
|
||||
|
||||
|
||||
void chatterCallback(const sensor_msgs::Imu& imuSub_msg)
|
||||
{
|
||||
//printing the data of the quaternion in the terminal:
|
||||
std::cout << "------------------------------------------------" << std::endl;
|
||||
std::cout << "Quaternation x: ";
|
||||
std::cout << imuSub_msg.orientation.x << std::endl;
|
||||
std::cout << "Quaternation y: ";
|
||||
std::cout << imuSub_msg.orientation.y << std::endl;
|
||||
std::cout << "Quaternation z: ";
|
||||
std::cout << imuSub_msg.orientation.z << std::endl;
|
||||
std::cout << "Quaternation w: ";
|
||||
std::cout << imuSub_msg.orientation.w << std::endl;
|
||||
std::cout << "------------------------------------------------" << std::endl;
|
||||
|
||||
//converting the quaternion into roll, pitch and yaw angles (in the "unit" rad)
|
||||
tf::Quaternion quat;
|
||||
tf::quaternionMsgToTF(imuSub_msg.orientation, quat);
|
||||
tf::Matrix3x3(quat).getRPY(roll, pitch, yaw);
|
||||
|
||||
//converting the roll, pitch and yaw values from the "unit" rad into the unit degrees
|
||||
roll = (roll * 360)/(2*pi);
|
||||
pitch = (pitch * 360)/(2*pi);
|
||||
yaw = (yaw * 360)/(2*pi);
|
||||
|
||||
//printing the roll, pitch and yaw values in the terminal
|
||||
std::cout << "roll: ";
|
||||
std::cout << roll << std::endl;
|
||||
std::cout << "pitch: ";
|
||||
std::cout << pitch << std::endl;
|
||||
std::cout << "yaw: ";
|
||||
std::cout << yaw << std::endl;
|
||||
|
||||
//calculating the linear velocity and the rotation speed values based on the angle the sensor is tilted (pitch and roll angles)
|
||||
linearVelocity = (linearVelFactor*pitch)/90;
|
||||
angularRotationSpeed = (-1)*(rotSpeedFactor*roll)/90;
|
||||
|
||||
//writing the previously calculated linear velocity and rotationspeed values in the message in order to publish the message to the cmd_vel topic (geometry_msgs/Twist)
|
||||
cmd_vel_msg.linear.x = linearVelocity;
|
||||
cmd_vel_msg.angular.z = angularRotationSpeed;
|
||||
|
||||
//publishing the message to the topic
|
||||
cmd_vel_Publisher.publish(cmd_vel_msg);
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
//printing information to the terminal
|
||||
std::cout << "The imuOrientToCmdVelTranslater was started ..." << std::endl;
|
||||
std::cout << "The linearVelFactor is: ";
|
||||
std::cout << linearVelFactor << std::endl;
|
||||
std::cout << "The rotSpeedFactor is: ";
|
||||
std::cout << rotSpeedFactor << std::endl;
|
||||
|
||||
//setting up the node, subscriber and publisher
|
||||
ros::init(argc, argv, "imuOrientToCmdVelTranslater_Node");
|
||||
ros::NodeHandle nh;
|
||||
ros::Subscriber imuOrientationSubscriber = nh.subscribe("imu/data", 1000, chatterCallback);
|
||||
cmd_vel_Publisher = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1000);
|
||||
|
||||
ros::spin();
|
||||
|
||||
return 0;
|
||||
}
|
9
Software Files/ROS Workspace/src/urdf/o2s_assem.csv
Normal file
@ -0,0 +1,9 @@
|
||||
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
|
||||
base_link,-0.0374777931065171,-0.000742607274570373,0.0517646177576365,0,0,0,5.79174328389446,0.0142969060262334,-4.92784367063061E-08,4.92627122966751E-05,0.0341323035296294,-2.71693609467846E-08,0.0398544878636473,0,0,0,0,0,0,package://o2s_robot/meshes/base_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://o2s_robot/meshes/base_link.STL,,o2s_base-1,CB,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
|
||||
rightwheel,-1.2143E-17,0.033904,1.3878E-17,0,0,0,1.0582,0.0018538,-1.2518E-19,-7.2208E-20,0.0031139,1.5395E-18,0.0018538,0,0,0,0,0,0,package://o2s_robot/meshes/rightwheel.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://o2s_robot/meshes/rightwheel.STL,,Main_Wheel-4,CRW,Axis1,rightwheel,continuous,-0.12418,0.185,-0.063,0,0,3.1416,base_link,0,1,0,1,1,,,,,,,,,,
|
||||
leftwheel,-2.4286E-17,-0.033904,4.1633E-17,0,0,0,1.0582,0.0018538,8.3854E-19,9.7745E-20,0.0031139,1.3019E-19,0.0018538,0,0,0,0,0,0,package://o2s_robot/meshes/leftwheel.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://o2s_robot/meshes/leftwheel.STL,,Main_Wheel-3,CLW,Axis2,leftwheel,continuous,-0.12418,-0.185,-0.063,0,0,-3.1416,base_link,0,-1,0,1,1,,,,,,,,,,
|
||||
casterwheel,-0.0032546,0.0053327,0.013127,0,0,0,0.10255,9.4829E-05,-2.3412E-06,1.3145E-05,0.00012884,8.5135E-07,5.2207E-05,0,0,0,0,0,0,package://o2s_robot/meshes/casterwheel.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://o2s_robot/meshes/casterwheel.STL,,Wheel-2,CC,Axis3,casterwheel,fixed,0.25029,-0.01098,-0.1075,0,0,0,base_link,0,0,0,,,,,,,,,,,,
|
||||
lidar,0.00050486,-3.7855E-05,-0.025753,0,0,0,0.2064,0.00011156,-1.2701E-07,-1.6019E-06,0.00010988,1.201E-07,0.0001391,0,0,0,0,0,0,package://o2s_robot/meshes/lidar.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://o2s_robot/meshes/lidar.STL,,Lidar_Sensor-3,CL,Axis_lidar,lidar,continuous,0.00082049,0.00875,0.12332,0,0,0,base_link,0,0,1,,,,,,,,,,,,
|
||||
imu,-0.015015,-0.00012812,0.00021369,0,0,0,0.05157,1.5728E-05,-1.2026E-09,1.5815E-09,8.9379E-06,-2.1887E-10,1.4344E-05,0,0,0,0,0,0,package://o2s_robot/meshes/imu.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://o2s_robot/meshes/imu.STL,,MPU-2,Ci,,imu,fixed,0.05082,-0.0047896,0.053918,0,0,0,base_link,0,0,0,,,,,,,,,,,,
|
||||
camerad435i,0.0094812,3.7095E-05,-7.9734E-05,0,0,0,0.032264,2.2098E-05,-1.4651E-10,2.902E-10,1.9467E-06,8.3417E-11,2.1858E-05,0,0,0,0,0,0,package://o2s_robot/meshes/camerad435i.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://o2s_robot/meshes/camerad435i.STL,,Camera2-1,Cca1,,camerad435i,fixed,-0.20718,-0.08268,0.17016,0,0,0,base_link,0,0,0,,,,,,,,,,,,
|
||||
camerat265,0.0061266,3.8568E-05,-1.9004E-05,0,0,0,0.030988,3.0221E-05,-1.6541E-10,4.8935E-11,1.9363E-06,9.2265E-11,2.9002E-05,0,0,0,0,0,0,package://o2s_robot/meshes/camerat265.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://o2s_robot/meshes/camerat265.STL,,Camera1-4,Cca2,Axis_camerat265,camerat265,prismatic,-0.20118,0.080908,0.16952,0,0,0,base_link,0,1,0,0,0,0,0,,,,,,,,
|
|
28
Software Files/ROS Workspace/src/urdf/o2s_materials.xacro
Normal file
@ -0,0 +1,28 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="o2s_robot" xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
|
||||
<material name="yellow">
|
||||
<color rgba="1 1 0.5 1"/>
|
||||
</material>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0 0 0 1"/>
|
||||
</material>
|
||||
|
||||
<material name="orange">
|
||||
<color rgba="1 0.3 0.1 1"/>
|
||||
</material>
|
||||
|
||||
<material name="blue">
|
||||
<color rgba="0.2 0.2 1 1"/>
|
||||
</material>
|
||||
|
||||
<material name="grey">
|
||||
<color rgba="0.4 0.4 0.4 1"/>
|
||||
</material>
|
||||
|
||||
</robot>
|
252
Software Files/ROS Workspace/src/urdf/o2s_robot.xacro
Normal file
@ -0,0 +1,252 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
|
||||
<robot name="o2s_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:include filename="$(find o2s_robot)/urdf/o2s_materials.xacro" />
|
||||
<xacro:include filename="$(find o2s_robot)/gazebo/o2s_gazebo_materials.gazebo" />
|
||||
<xacro:include filename="$(find o2s_robot)/gazebo/o2s_gazebo_physics.gazebo" />
|
||||
<xacro:include filename="$(find o2s_robot)/gazebo/o2s_gazebo_plugins.gazebo" />
|
||||
|
||||
<!--******** Define intertial property macros ********** -->
|
||||
|
||||
<xacro:macro name="footprint_inertia" params="m w h d">
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="${m}"/>
|
||||
<inertia ixx="${(m/12) * (h*h + d*d)}" ixy="0.0" ixz="0.0" iyy="${(m/12) * (w*w + d*d)}" iyz="0.0" izz="${(m/12) * (w*w + h*h)}"/>
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- ****************** Robot bases *************************** -->
|
||||
<!-- Define the center of the main robot chassis projected on the ground -->
|
||||
<link name="base_footprint">
|
||||
<xacro:footprint_inertia m="0" w="0" d="0" h="0"/>
|
||||
</link>
|
||||
|
||||
<!-- The base footprint of the robot is located underneath the chassis -->
|
||||
<joint name="base_joint" type="fixed">
|
||||
<parent link="base_link"/>
|
||||
<child link="base_footprint"/>
|
||||
<origin xyz="0.0 0.0 -0.14" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="base_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.0374777931065171 -0.000742607274570373 0.0517646177576365" rpy="0 0 0" />
|
||||
<mass value="5.79174328389446" />
|
||||
<inertia ixx="0.0142969060262334" ixy="-4.92784367063061E-08" ixz="4.92627122966751E-05" iyy="0.0341323035296294" iyz="-2.71693609467846E-08" izz="0.0398544878636473" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/base_link.STL" />
|
||||
</geometry>
|
||||
<material name="white">
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/base_link.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="rightwheel_link">
|
||||
<inertial>
|
||||
<origin xyz="-1.2143E-17 0.033904 1.3878E-17" rpy="0 0 0" />
|
||||
<mass value="1.0582" />
|
||||
<inertia ixx="0.0018538" ixy="-1.2518E-19" ixz="-7.2208E-20" iyy="0.0031139" iyz="1.5395E-18" izz="0.0018538" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/rightwheel.STL" />
|
||||
</geometry>
|
||||
<material name="black">
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/rightwheel.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rightwheel_joint" type="continuous">
|
||||
<origin xyz="-0.12418 0.185 -0.063" rpy="0 0 3.1416" />
|
||||
<parent link="base_link" />
|
||||
<child link="rightwheel_link" />
|
||||
<axis xyz="0 1 0" />
|
||||
</joint>
|
||||
|
||||
<link name="leftwheel_link">
|
||||
<inertial>
|
||||
<origin xyz="-2.4286E-17 -0.033904 4.1633E-17" rpy="0 0 0" />
|
||||
<mass value="1.0582" />
|
||||
<inertia ixx="0.0018538" ixy="8.3854E-19" ixz="9.7745E-20" iyy="0.0031139" iyz="1.3019E-19" izz="0.0018538" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/leftwheel.STL" />
|
||||
</geometry>
|
||||
<material name="black">
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/leftwheel.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="leftwheel_joint" type="continuous">
|
||||
<origin xyz="-0.12418 -0.185 -0.063" rpy="0 0 -3.1416" />
|
||||
<parent link="base_link" />
|
||||
<child link="leftwheel_link" />
|
||||
<axis xyz="0 1 0" />
|
||||
</joint>
|
||||
|
||||
<link name="casterwheel_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.0032546 0.0053327 0.013127" rpy="0 0 0" />
|
||||
<mass value="0.10255" />
|
||||
<inertia ixx="9.4829E-05" ixy="-2.3412E-06" ixz="1.3145E-05" iyy="0.00012884" iyz="8.5135E-07" izz="5.2207E-05" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/casterwheel.STL" />
|
||||
</geometry>
|
||||
<material name="blue">
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/casterwheel.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="casterwheel_joint" type="fixed">
|
||||
<origin xyz="0.25029 -0.01098 -0.1075" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="casterwheel_link" />
|
||||
<axis xyz="0 0 0" />
|
||||
</joint>
|
||||
|
||||
<link name="lidar_link">
|
||||
<inertial>
|
||||
<origin xyz="0.00050486 -3.7855E-05 -0.025753" rpy="0 0 0" />
|
||||
<mass value="0.2064" />
|
||||
<inertia ixx="0.00011156" ixy="-1.2701E-07" ixz="-1.6019E-06" iyy="0.00010988" iyz="1.201E-07" izz="0.0001391" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/lidar.STL" />
|
||||
</geometry>
|
||||
<material name="grey">
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/lidar.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="lidar_joint" type="fixed">
|
||||
<origin xyz="0.00082049 0.00875 0.12332" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="lidar_link" />
|
||||
<axis xyz="0 0 1" />
|
||||
</joint>
|
||||
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.015015 -0.00012812 0.00021369" rpy="0 0 0" />
|
||||
<mass value="0.05157" />
|
||||
<inertia ixx="1.5728E-05" ixy="-1.2026E-09" ixz="1.5815E-09" iyy="8.9379E-06" iyz="-2.1887E-10" izz="1.4344E-05" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/imu.STL" />
|
||||
</geometry>
|
||||
<material name="black">
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/imu.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<origin xyz="0.05082 -0.0047896 0.053918" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="imu_link" />
|
||||
<axis xyz="0 0 0" />
|
||||
</joint>
|
||||
|
||||
<link name="camerad435i_link">
|
||||
<inertial>
|
||||
<origin xyz="0.0094812 3.7095E-05 -7.9734E-05" rpy="0 0 0" />
|
||||
<mass value="0.032264" />
|
||||
<inertia ixx="2.2098E-05" ixy="-1.4651E-10" ixz="2.902E-10" iyy="1.9467E-06" iyz="8.3417E-11" izz="2.1858E-05" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/camerad435i.STL" />
|
||||
</geometry>
|
||||
<material name="white">
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/camerad435i.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="camerad435i_joint" type="fixed">
|
||||
<origin xyz="-0.20718 -0.08268 0.17016" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="camerad435i_link" />
|
||||
<axis xyz="0 0 0" />
|
||||
</joint>
|
||||
|
||||
<link name="camerat265_link">
|
||||
<inertial>
|
||||
<origin xyz="0.0061266 3.8568E-05 -1.9004E-05" rpy="0 0 0" />
|
||||
<mass value="0.030988" />
|
||||
<inertia ixx="3.0221E-05" ixy="-1.6541E-10" ixz="4.8935E-11" iyy="1.9363E-06" iyz="9.2265E-11" izz="2.9002E-05" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/camerat265.STL" />
|
||||
</geometry>
|
||||
<material name="white">
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://o2s_robot/meshes/camerat265.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="camerat265_joint" type="fixed">
|
||||
<origin xyz="-0.20118 0.080908 0.16952" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="camerat265_link" />
|
||||
<axis xyz="0 0 0" />
|
||||
</joint>
|
||||
|
||||
</robot>
|
||||
|
||||
|