Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 56 additions & 0 deletions orange_description/xacro/orange_robot_simulation.gazebo
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
<?xml version="1.0"?>
<robot>
<!--front wheels-->
<gazebo reference="left_wheel">
<mu1>5.0</mu1>
<mu2>5.0</mu2>
<kp>1000000.0</kp>
<kd>100.0</kd>
<minDepth>0.001</minDepth>
<maxVel>1.0</maxVel>
</gazebo>
<gazebo reference="right_wheel">
<mu1>5.0</mu1>
<mu2>5.0</mu2>
<kp>1000000.0</kp>
<kd>100.0</kd>
<minDepth>0.001</minDepth>
<maxVel>1.0</maxVel>
</gazebo>
<!--caster-->
<gazebo reference="left_caster_link">
<mu1>0.0</mu1>
<mu2>0.0</mu2>
</gazebo>
<gazebo reference="right_caster_link">
<mu1>0.0</mu1>
<mu2>0.0</mu2>
</gazebo>
<!--plugins-->
<gazebo>
<plugin name="diff_drive_controller" filename="libgazebo_ros_diff_drive.so">
<update_rate>30</update_rate>
<left_joint>left_wheel_hinge</left_joint>
<right_joint>right_wheel_hinge</right_joint>
<wheel_separation>0.5672</wheel_separation>
<wheel_diameter>0.203</wheel_diameter>
<max_wheel_torque>20</max_wheel_torque>
<max_wheel_acceleration>2.0</max_wheel_acceleration>
<command_topic>cmd_vel</command_topic>
<publish_odom>false</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>false</publish_wheel_tf>
<odometry_topic>odom</odometry_topic>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_footprint</robot_base_frame>
</plugin>
<plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>30</update_rate>
<joint_name>left_wheel_hinge</joint_name>
<joint_name>right_wheel_hinge</joint_name>
</plugin>
</gazebo>
</robot>
146 changes: 146 additions & 0 deletions orange_description/xacro/orange_robot_simulation.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,146 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="orange_robot">
<!--import gazebo reference-->
<xacro:include filename="$(find orange_description)/xacro/orange_robot_simulation.gazebo"/>
<!--import 2D LiDAR model-->
<xacro:include filename="$(find orange_description)/xacro/sensors/hokuyo.xacro"/>
<xacro:sensor_hokuyo name="hokuyo" parent="base_link" min_angle="-1.22" max_angle="1.22" samples="720">
<origin xyz="0.1075 0.0 0.1085" rpy="0.0 0.0 0.0"/>
</xacro:sensor_hokuyo>
<!--import 3D LiDAR model-->
<!--bringup-->
<!--<xacro:include filename="$(find orange_description)/xacro/sensors/livox.xacro"/>
<xacro:sensor_livox name="livox_frame" parent="base_link" min_angle="-2.35619" max_angle="2.35619" samples="720">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:sensor_livox>-->
<!--simulation-->
<xacro:include filename="$(find orange_description)/xacro/sensors/livox_simulation.xacro"/>
<xacro:mid360 name="livox" parent="base_link" topic="mid360">
<origin xyz="-0.0185 0.0 0.8985" rpy="${pi} 0.0 0.0"/>
</xacro:mid360>
<!--import imu model-->
<xacro:include filename="$(find orange_description)/xacro/sensors/imu.xacro"/>
<xacro:sensor_imu name="imu" parent="base_link" size="0.05 0.05 0.05">
<origin xyz="-0.253 0.0 0.068" rpy="0.0 0.0 0.0"/>
</xacro:sensor_imu>
<!--base footprint-->
<link name="base_footprint"/>
<!--base link-->
<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.1015" rpy="0 0 0"/>
</joint>
<link name="base_link">
<visual>
<origin xyz="0.0775 0.25275 0.6425" rpy="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find orange_description)/meshes/chassis.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="-0.1995 0.0 0.341" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.549 0.5055 0.603"/>
</geometry>
</collision>
<inertial>
<mass value="27.1"/>
<origin xyz="-0.1995 0.0 0.19" rpy="0.0 0.0 0.0"/>
<inertia ixx="0.78032248125" ixy="0.0" ixz="0.0" iyy="0.883913925" iyz="0.0" izz="1.25773640625"/>
</inertial>
</link>
<!--caster-->
<joint name="left_caster_hinge" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<child link="left_caster_link"/>
<parent link="base_link"/>
</joint>
<joint name="right_caster_hinge" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<child link="right_caster_link"/>
<parent link="base_link"/>
</joint>
<link name="left_caster_link">
<visual>
<origin xyz="-0.4815 0.145 -0.039" rpy="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find orange_description)/meshes/left_caster.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="-0.4815 0.145 -0.039" rpy="0.0 1.57079632679 1.57079632679"/>
<geometry>
<sphere radius="0.0625"/>
</geometry>
</collision>
</link>
<link name="right_caster_link">
<visual>
<origin xyz="-0.4815 -0.145 -0.039" rpy="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find orange_description)/meshes/right_caster.dae"/>
<sphere radius="0.0625"/>
</geometry>
</visual>
<collision>
<origin xyz="-0.4815 -0.145 -0.039" rpy="0.0 1.57079632679 1.57079632679"/>
<geometry>
<sphere radius="0.0625"/>
</geometry>
</collision>
</link>
<!--front wheels-->
<joint type="revolute" name="left_wheel_hinge">
<origin xyz="0.0 0.2834 0.0" rpy="0.0 0.0 0.0"/>
<child link="left_wheel">left_wheel</child>
<parent link="base_link">base_link</parent>
<axis xyz="0 1 0"/>
<limit effort="100" velocity="100.0" lower="-5000" upper="5000"/>
</joint>
<joint type="revolute" name="right_wheel_hinge">
<origin xyz="0.0 -0.2834 0.0" rpy="0.0 0.0 0.0"/>
<child link="right_wheel">right_wheel</child>
<parent link="base_link">base_link</parent>
<axis xyz="0 1 0"/>
<limit effort="100" velocity="100.0" lower="-5000" upper="5000"/>
</joint>
<link name="left_wheel">
<visual name="visual">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find orange_description)/meshes/front_wheel.dae"/>
</geometry>
</visual>
<collision name="collision">
<origin xyz="0.0 0.0 0.0" rpy="0.0 1.57079632679 1.57079632679"/>
<geometry>
<cylinder length="0.047" radius="0.1015"/>
</geometry>
</collision>
<inertial>
<mass value="3.4"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 1.57079632679 1.57079632679"/>
<inertia ixx="0.00938279583" ixy="0.0" ixz="0.0" iyy="0.00938279583" iyz="0.0" izz="0.017513825"/>
</inertial>
</link>
<link name="right_wheel">
<visual name="visual">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file://$(find orange_description)/meshes/front_wheel.dae"/>
</geometry>
</visual>
<collision name="collision">
<origin xyz="0.0 0.0 0.0" rpy="0.0 1.57079632679 1.57079632679"/>
<geometry>
<cylinder length="0.047" radius="0.1015"/>
</geometry>
</collision>
<inertial>
<mass value="3.4"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 1.57079632679 1.57079632679"/>
<inertia ixx="0.00938279583" ixy="0.0" ixz="0.0" iyy="0.00938279583" iyz="0.0" izz="0.017513825"/>
</inertial>
</link>
</robot>
77 changes: 77 additions & 0 deletions orange_description/xacro/sensors/livox_simulation.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926"/>
<xacro:property name="laser_min_range" value="0.1"/>
<xacro:property name="laser_max_range" value="200.0"/>
<xacro:property name="samples" value="40000"/>
<xacro:property name="resolution" value="0.002"/>
<xacro:property name="noise_mean" value="0.0"/>
<xacro:property name="noise_stddev" value="0.01"/>
<xacro:property name="mass" value="0.4"/>
<xacro:property name="length" value="0.1"/>
<xacro:property name="width" value="0.06"/>
<xacro:property name="height" value="0.06"/>
<xacro:macro name="box_inertia" params="m w h d">
<inertial>
<origin xyz="0 0 0" rpy="${pi/2} 0 ${pi/2}"/>
<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>
<xacro:macro name="mid360" params="name:='' parent:= 'base_link' topic:='mid360' *origin ">
<link name="${name}">
<xacro:box_inertia m="${length}" w="${width}" d="${length}" h="${height}"/>
<visual>
<geometry>
<box size="${length} ${width} ${height}"/>
</geometry>
</visual>
</link>
<joint name="${name}_joint" type="fixed">
<parent link="${parent}"/>
<child link="${name}"/>
<xacro:insert_block name="origin"/>
</joint>
<gazebo reference="${name}">
<sensor type="ray" name="${name}">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>10</update_rate>
<!-- This ray plgin is only for visualization. -->
<plugin name="${name}_plugin" filename="libros2_livox.so">
<ray>
<scan>
<horizontal>
<samples>100</samples>
<resolution>1</resolution>
<min_angle>${0}</min_angle>
<max_angle>${2*M_PI}</max_angle>
</horizontal>
<vertical>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>${-7.22/180*M_PI}</min_angle>
<max_angle>${55.22/180*M_PI}</max_angle>
</vertical>
</scan>
<range>
<min>${laser_min_range}</min>
<max>${laser_max_range}</max>
<resolution>${resolution}</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>${noise_mean}</mean>
<stddev>${noise_stddev}</stddev>
</noise>
</ray>
<visualize>false</visualize>
<samples>${samples}</samples>
<downsample>1</downsample>
<csv_file_name>$(find ros2_livox_simulation)/scan_mode/mid360.csv</csv_file_name>
<topic>${topic}</topic>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
6 changes: 3 additions & 3 deletions orange_gazebo/launch/empty_world.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@
<arg name="imu_topic" default="/imu"/>
<arg name="fusion_odom_topic" default="/fusion/odom"/>
<arg name="world_file_path" default="$(find-pkg-share gazebo_ros)/worlds/empty.world"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot.xacro"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot_simulation.xacro"/>
<!-- ground_segmentation -->
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation.launch.xml">
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation_simulation.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="input_topic" value="/mid360_PointCloud2"/>
<arg name="ground_output_topic" value="$(var livox_points_topic)/ground"/>
Expand All @@ -28,7 +28,7 @@
<arg name="scan_out" value="$(var velodyne_scan_topic)"/>
</include>-->
<!-- pointcloud2_to_laserscan -->
<include file="$(find-pkg-share orange_sensor_tools)/launch/livox_to_pointcloud2_laserscan.launch.py">
<include file="$(find-pkg-share orange_sensor_tools)/launch/livox_to_pointcloud2_laserscan_simulation.launch.py">
<arg name="cloud_in" value="$(var livox_points_topic)/obstacle"/>
<arg name="scan_out" value="$(var livox_scan_topic)"/>
</include>
Expand Down
6 changes: 3 additions & 3 deletions orange_gazebo/launch/orange_hosei.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,12 +13,12 @@
<arg name="imu_topic" default="/imu"/>
<arg name="fusion_odom_topic" default="/fusion/odom"/>
<arg name="world_file_path" default="$(find-pkg-share orange_gazebo)/worlds/orange_hosei.world"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot.xacro"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot_simulation.xacro"/>
<arg name="x" default="0.0"/>
<arg name="y" default="0.0"/>
<arg name="yaw" default="0.0"/>
<!-- ground_segmentation -->
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation.launch.xml">
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation_simulation.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="input_topic" value="/mid360_PointCloud2"/>
<arg name="ground_output_topic" value="$(var livox_points_topic)/ground"/>
Expand All @@ -31,7 +31,7 @@
<arg name="scan_out" value="$(var velodyne_scan_topic)"/>
</include>-->
<!-- pointcloud2_to_laserscan -->
<include file="$(find-pkg-share orange_sensor_tools)/launch/livox_to_pointcloud2_laserscan.launch.py">
<include file="$(find-pkg-share orange_sensor_tools)/launch/livox_to_pointcloud2_laserscan_simulation.launch.py">
<arg name="cloud_in" value="$(var livox_points_topic)/obstacle"/>
<arg name="scan_out" value="$(var livox_scan_topic)"/>
</include>
Expand Down
6 changes: 3 additions & 3 deletions orange_gazebo/launch/orange_igvc.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@
<arg name="imu_topic" default="/imu"/>
<arg name="fusion_odom_topic" default="/fusion/odom"/>
<arg name="world_file_path" default="$(find-pkg-share orange_gazebo)/worlds/orange_igvc.world"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot.xacro"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot_simulation.xacro"/>
<!-- ground_segmentation -->
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation.launch.xml">
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation_simulation.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="input_topic" value="/mid360_PointCloud2"/>
<arg name="ground_output_topic" value="$(var livox_points_topic)/ground"/>
Expand All @@ -28,7 +28,7 @@
<arg name="scan_out" value="$(var velodyne_scan_topic)"/>
</include>-->
<!-- pointcloud2_to_laserscan -->
<include file="$(find-pkg-share orange_sensor_tools)/launch/livox_to_pointcloud2_laserscan.launch.py">
<include file="$(find-pkg-share orange_sensor_tools)/launch/livox_to_pointcloud2_laserscan_simulation.launch.py">
<arg name="cloud_in" value="$(var livox_points_topic)/obstacle"/>
<arg name="scan_out" value="$(var livox_scan_topic)"/>
</include>
Expand Down
6 changes: 3 additions & 3 deletions orange_gazebo/launch/orange_world.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@
<arg name="imu_topic" default="/imu"/>
<arg name="fusion_odom_topic" default="/fusion/odom"/>
<arg name="world_file_path" default="$(find-pkg-share orange_gazebo)/worlds/orange_world.world"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot.xacro"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot_simulation.xacro"/>
<!-- ground_segmentation -->
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation.launch.xml">
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation_simulation.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="input_topic" value="/mid360_PointCloud2"/>
<arg name="ground_output_topic" value="$(var livox_points_topic)/ground"/>
Expand All @@ -28,7 +28,7 @@
<arg name="scan_out" value="$(var velodyne_scan_topic)"/>
</include>-->
<!-- pointcloud2_to_laserscan -->
<include file="$(find-pkg-share orange_sensor_tools)/launch/livox_to_pointcloud2_laserscan.launch.py">
<include file="$(find-pkg-share orange_sensor_tools)/launch/livox_to_pointcloud2_laserscan_simulation.launch.py">
<arg name="cloud_in" value="$(var livox_points_topic)/obstacle"/>
<arg name="scan_out" value="$(var livox_scan_topic)"/>
</include>
Expand Down
5 changes: 4 additions & 1 deletion orange_ros2.rosinstall
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

このシミュレータ使ったんですね。ありがとうございます。
もしかしたら、複数人が同時に使うとサーバが落ちるかもしれないです。。。

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ROS_DOMAIN_IDでは解決できないか検証してみます

Original file line number Diff line number Diff line change
Expand Up @@ -38,4 +38,7 @@
local-name: pcd_convert
uri: https://github.com/KBKN-Autonomous-Robotics-Lab/pcd_convert.git
version: main

- git:
local-name: livox_laser_simulation_RO2
uri: https://github.com/stm32f303ret6/livox_laser_simulation_RO2.git
version: main
Loading