Closed AmeliaEScott closed 4 years ago
Found this: https://github.com/aionrobotics/r1_ugv_sim
This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.
@ItsTimmy is this still on your TODO?
This was never on my personal TODO list, but I think it is important and should still be done.
I will take a look at this this week end. I don't think it will take too long to do. However, @julianoes the link you have doesn't have a license. Would it be okay to adapt the xacro files into sdf and have it it sitl_gazebo
?
the link you have doesn't have a license
I don't know but I would copy it and add a reference to where it's from in a comment. I would hope aionrobotics are ok that we use and thus advertise their product in our sim.
This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.
I have the same trouble. Can anyone solve it
@weiLiangHare Which issue are you having? This is not a bug, but a place holder for possible enhancement
I hope sitlgazebo can support Aion R1 rover simulation.I tried to add it myself.But there are problems。I work on the this branch https://github.com/PX4/Firmware/tree/pr-sitl-r1,and my sdf is here。It can work, but it is not ideal. @Jaeyoung-Lim My video https://www.youtube.com/watch?v=HxnZzFQkIYs&feature=youtu.be_ Thank you for your reply.
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="aion_robotics_r1_rover">
<link name="base_link">
<collision name="collision">
<!-- <pose>0 0 -0.3 0 0 0</pose> -->
<pose>0 0 0.1 0 0 0</pose>
<geometry>
<box>
<size>1.0074 0.5709 0.2675</size>
</box>
</geometry>
</collision>
<inertial>
<mass>33.855</mass>
<pose>-0.0856132 -0.000839955 0.238145 0 0 0</pose>
<inertia>
<ixx>2.2343</ixx>
<ixy>-0.023642</ixy>
<ixz>0.275174</ixz>
<iyy>3.42518</iyy>
<iyz>0.00239624</iyz>
<izz>2.1241</izz>
</inertia>
</inertial>
<visual name="base">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/base_link.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- Top Plate -->
<visual name="top_plate">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/top_plate.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Yellow</name>
</script>
</material>
</visual>
<!-- Front Bumper -->
<visual name="front_bumper">
<pose>0.47 0 0.091 0 0 0</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/bumper.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- Rear Bumper -->
<visual name="rear_bumper">
<pose>-0.47 0 0.091 0 0 3.141</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/bumper.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- User Rail -->
<visual name="user_rail">
<pose>0.272 0 0.245 0 0 0</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/user_rail.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<!-- Back Left Wheel -->
<link name="back_left_wheel">
<pose>-0.256 0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name="back_left_wheel_collision">
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="back_left_wheel">
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/wheel.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name="back_left_joint" type="revolute">
<parent>base_link</parent>
<child>back_left_wheel</child>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>true</use_parent_model_frame>
</axis>
<physics>
<ode>
<limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit>
</ode>
</physics>
</joint>
<!-- Back Right Wheel -->
<link name="back_right_wheel">
<pose>-0.256 -0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name="back_right_wheel_collision">
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="back_right_wheel">
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/wheel.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name="back_right_joint" type="revolute">
<parent>base_link</parent>
<child>back_right_wheel</child>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>true</use_parent_model_frame>
</axis>
<physics>
<ode>
<limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit>
</ode>
</physics>
</joint>
<!-- Front Left Wheel -->
<link name="front_left_wheel">
<pose>0.256 0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name="front_left_wheel_collision">
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="front_left_wheel">
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/wheel.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name="front_left_joint" type="revolute">
<parent>base_link</parent>
<child>front_left_wheel</child>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>true</use_parent_model_frame>
</axis>
<physics>
<ode>
<limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit>
</ode>
</physics>
</joint>
<!-- Front Right Wheel -->
<link name="front_right_wheel">
<pose>0.256 -0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name="front_right_wheel_collision">
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="front_right_wheel">
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh>
<uri>model://aion_robotics_r1_rover/meshes/wheel.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<link name='aion_robotics_r1_rover/imu_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
</link>
<joint name='aion_robotics_r1_rover/imu_joint' type='revolute'>
<child>aion_robotics_r1_rover/imu_link</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<joint name="front_right_joint" type="revolute">
<parent>base_link</parent>
<child>front_right_wheel</child>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>true</use_parent_model_frame>
</axis>
<physics>
<ode>
<limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit>
</ode>
</physics>
</joint>
<plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
<robotNamespace/>
<pubRate>10</pubRate>
<baroTopic>/baro</baroTopic>
</plugin>
<plugin name='gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
<robotNamespace></robotNamespace>
<linkName>aion_robotics_r1_rover/imu_link</linkName>
<imuTopic>/imu</imuTopic>
<gyroscopeNoiseDensity>0.0003394</gyroscopeNoiseDensity>
<gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
<gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
<gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
<accelerometerNoiseDensity>0.004</accelerometerNoiseDensity>
<accelerometerRandomWalk>0.006</accelerometerRandomWalk>
<accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
<accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
</plugin>
<plugin name="gps_plugin" filename="libgazebo_gps_plugin.so">
<robotNamespace></robotNamespace>
<gpsNoise>true</gpsNoise>
</plugin>
<plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'>
<robotNamespace/>
<pubRate>20</pubRate>
<noiseDensity>0.0004</noiseDensity>
<randomWalk>6.4e-06</randomWalk>
<biasCorrelationTime>600</biasCorrelationTime>
<magTopic>/mag</magTopic>
</plugin>
<plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
<robotNamespace></robotNamespace>
<imuSubTopic>/imu</imuSubTopic>
<gpsSubTopic>/gps</gpsSubTopic>
<magSubTopic>/mag</magSubTopic>
<baroSubTopic>/baro</baroSubTopic>
<mavlink_addr>INADDR_ANY</mavlink_addr>
<mavlink_udp_port>14560</mavlink_udp_port>
<serialEnabled>false</serialEnabled>
<serialDevice>/dev/ttyACM0</serialDevice>
<baudRate>921600</baudRate>
<qgc_addr>INADDR_ANY</qgc_addr>
<qgc_udp_port>14550</qgc_udp_port>
<hil_mode>false</hil_mode>
<hil_state_level>false</hil_state_level>
<enable_lockstep>true</enable_lockstep>
<use_tcp>true</use_tcp>
<motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
<control_channels>
<channel name="front_left_wheel_drive">
<input_index>0</input_index>
<input_offset>0</input_offset>
<input_scaling>20</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
<joint_name>front_left_joint</joint_name>
<joint_control_pid>
<p>10</p>
<i>1</i>
<d>0</d>
<iMax>800</iMax>
<iMin>-800</iMin>
<cmdMax>1200</cmdMax>
<cmdMin>-1200</cmdMin>
</joint_control_pid>
</channel>
<channel name="back_left_wheel_drive">
<input_index>0</input_index>
<input_offset>0</input_offset>
<input_scaling>20</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
<joint_name>back_left_joint</joint_name>
<joint_control_pid>
<p>10</p>
<i>1</i>
<d>0</d>
<iMax>800</iMax>
<iMin>-800</iMin>
<cmdMax>1200</cmdMax>
<cmdMin>-1200</cmdMin>
</joint_control_pid>
</channel>
<channel name="front_right_wheel_drive">
<input_index>1</input_index>
<input_offset>0</input_offset>
<input_scaling>20</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
<joint_name>front_right_joint</joint_name>
<joint_control_pid>
<p>10</p>
<i>1</i>
<d>0</d>
<iMax>800</iMax>
<iMin>-800</iMin>
<cmdMax>1200</cmdMax>
<cmdMin>-1200</cmdMin>
</joint_control_pid>
</channel>
<channel name="back_right_wheel_drive">
<input_index>1</input_index>
<input_offset>0</input_offset>
<input_scaling>20</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
<joint_name>back_right_joint</joint_name>
<joint_control_pid>
<p>10</p>
<i>1</i>
<d>0</d>
<iMax>800</iMax>
<iMin>-800</iMin>
<cmdMax>1200</cmdMax>
<cmdMin>-1200</cmdMin>
</joint_control_pid>
</channel>
</control_channels>
</plugin>
</model>
</sdf>
@weiLiangHare Cool video! I have added my WIP progress of the rover in https://github.com/PX4/sitl_gazebo/pull/394 , but I was having some problems on making the wheel dynamics correct.
@Jaeyoung-Lim Cool,good job.Am looking forward to
@Jaeyoung-Lim Is it possible to know the progress of the R1 integration in gazebo? Indeed because of the "situation", all of us are remotely working and thus I will investigate the simulation in order to move forward. So I will test the L1 controller in simulation. One more question, I guess that if PX4 is correctly configured the "wiring" with R1 motors is done automatically? Thank you
@FaboNo Currently there is not much progress, please feel free to move it forward. Currently the wiriing is already done with this PR. It's just with the current configuration of contact parameters the vehicle does not turn
@Jaeyoung-Lim oh I see but when I look at the video from @weiLiangHare looks like it can turn no? I will take the sdf file from @weiLiangHare and do some tests.
@FaboNo That would be a lot of help, thanks!
@Jaeyoung-Lim Awesome!!! On my side I have to make px4 and sitl gazebo working and then connect with ROS - I will follow the "px4/obstacle" instructions . Just few questions: When the PR will be approved the r1 rover will be added in stil_gazebo/models? This is a question I will ask about sitl_gazebo, is how to add a new model... Looks like the L1 controller is fully working now (besides moving backward), so it is able to handle lon/lat coordinates as well as cartesian coordinates (in case there is a SLAM in the loop) - I guess the answer is yes
@FaboNo I have linked the PR of the sitl_gazebo in #14652
When I use the aion r1_rover sdf model, I have troubles :
@ThomasRegis Please don't hijack the topic of this issue. If you have a new issue, please consider posting the description of your issue and instructions on how to reproduce it.
Describe problem solved by the proposed feature The Aion R1 Rover is being used as a development platform for rover support in PX4. The current rover model in Gazebo does not accurately reflect this rover.
Describe your preferred solution Add an accurate model of the Aion R1 rover for testing in Gazebo.
Additional context The existing rover model in Gazebo is a Polaris golf cart.