Skip to content
Snippets Groups Projects
Commit e3ee2da2 authored by Steven Macenski's avatar Steven Macenski
Browse files

adding more fully described parameters and setup

parent 08c41cb6
No related branches found
No related tags found
No related merge requests found
......@@ -117,7 +117,7 @@ def generate_launch_description():
declare_simulator_cmd = DeclareLaunchArgument(
'headless',
default_value='False',
default_value='True',
description='Whether to execute gzclient)')
declare_world_cmd = DeclareLaunchArgument(
......@@ -140,8 +140,7 @@ def generate_launch_description():
cmd=['gzclient'],
cwd=[launch_dir], output='screen')
urdf = os.path.join(
get_package_share_directory('turtlebot3_description'), 'urdf', 'turtlebot3_waffle.urdf')
urdf = os.path.join(bringup_dir, 'worlds', 'turtlebot3_waffle.urdf')
start_robot_state_publisher_cmd = Node(
condition=IfCondition(use_robot_state_pub),
......
......@@ -115,14 +115,17 @@ controller_server_rclcpp_node:
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 5
publish_frequency: 2
robot_base_frame: base_link
use_sim_time: True
global_frame: odom
plugin_names: ["obstacle_layer", "voxel_layer", "inflation_layer"]
plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
rolling_window: true
width: 3
height: 3
resolution: 0.05
plugin_names: ["obstacle_layer", "voxel_layer", "inflation_layer"]
plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
robot_radius: 0.22
inflation_layer:
cost_scaling_factor: 3.0
......@@ -139,8 +142,8 @@ local_costmap:
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.2
z_voxels: 10
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: pointcloud
......@@ -163,10 +166,15 @@ local_costmap:
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1
publish_frequency: 1
robot_base_frame: base_link
global_frame: map
use_sim_time: True
plugin_names: ["static_layer", "obstacle_layer", "voxel_layer", "inflation_layer"]
plugin_types: ["nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
robot_radius: 0.22
resolution: 0.05
obstacle_layer:
enabled: True
observation_sources: scan
......@@ -180,8 +188,8 @@ global_costmap:
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.2
z_voxels: 10
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: pointcloud
......
<?xml version="1.0" ?>
<robot name="turtlebot3_waffle" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- <xacro:include filename="$(find turtlebot3_description)/urdf/common_properties.urdf"/>
<xacro:property name="r200_cam_rgb_px" value="0.005"/>
<xacro:property name="r200_cam_rgb_py" value="0.018"/>
<xacro:property name="r200_cam_rgb_pz" value="0.013"/>
<xacro:property name="r200_cam_depth_offset" value="0.01"/> -->
<!-- Init colour -->
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="dark">
<color rgba="0.3 0.3 0.3 1.0"/>
</material>
<material name="light_black">
<color rgba="0.4 0.4 0.4 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.4235 0.0392 1.0"/>
</material>
<material name="brown">
<color rgba="0.8706 0.8118 0.7647 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<link name="base_footprint"/>
<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link" />
<origin xyz="0 0 0.010" rpy="0 0 0"/>
</joint>
<link name="base_link">
<visual>
<origin xyz="-0.064 0 0.0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot3_description/meshes/bases/waffle_base.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="light_black"/>
</visual>
<collision>
<origin xyz="-0.064 0 0.047" rpy="0 0 0"/>
<geometry>
<box size="0.266 0.266 0.094"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1.3729096e+00"/>
<inertia ixx="8.7002718e-03" ixy="-4.7576583e-05" ixz="1.1160499e-04"
iyy="8.6195418e-03" iyz="-3.5422299e-06"
izz="1.4612727e-02" />
</inertial>
</link>
<joint name="wheel_left_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_left_link"/>
<origin xyz="0.0 0.144 0.023" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="wheel_left_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0"/>
<geometry>
<mesh filename="package://turtlebot3_description/meshes/wheels/left_tire.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dark"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.018" radius="0.033"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="2.8498940e-02" />
<inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
iyy="1.1192413e-05" iyz="-1.4400107e-11"
izz="2.0712558e-05" />
</inertial>
</link>
<joint name="wheel_right_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_right_link"/>
<origin xyz="0.0 -0.144 0.023" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="wheel_right_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0"/>
<geometry>
<mesh filename="package://turtlebot3_description/meshes/wheels/right_tire.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dark"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.018" radius="0.033"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="2.8498940e-02" />
<inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
iyy="1.1192413e-05" iyz="-1.4400107e-11"
izz="2.0712558e-05" />
</inertial>
</link>
<joint name="caster_back_right_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_back_right_link"/>
<origin xyz="-0.177 -0.064 -0.004" rpy="-1.57 0 0"/>
</joint>
<link name="caster_back_right_link">
<collision>
<origin xyz="0 0.001 0" rpy="0 0 0"/>
<geometry>
<box size="0.030 0.009 0.020"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.005" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
<joint name="caster_back_left_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_back_left_link"/>
<origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/>
</joint>
<link name="caster_back_left_link">
<collision>
<origin xyz="0 0.001 0" rpy="0 0 0"/>
<geometry>
<box size="0.030 0.009 0.020"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.005" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="base_link"/>
<child link="imu_link"/>
<origin xyz="0.0 0 0.068" rpy="0 0 0"/>
</joint>
<link name="imu_link"/>
<joint name="scan_joint" type="fixed">
<parent link="base_link"/>
<child link="base_scan"/>
<origin xyz="-0.064 0 0.122" rpy="0 0 0"/>
</joint>
<link name="base_scan">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot3_description/meshes/sensors/lds.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dark"/>
</visual>
<collision>
<origin xyz="0.015 0 -0.0065" rpy="0 0 0"/>
<geometry>
<cylinder length="0.0315" radius="0.055"/>
</geometry>
</collision>
<inertial>
<mass value="0.114" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
<joint name="camera_joint" type="fixed">
<origin xyz="0.064 -0.065 0.094" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="camera_link"/>
</joint>
<link name="camera_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 1.57"/>
<geometry>
<mesh filename="package://turtlebot3_description/meshes/sensors/r200.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0.003 0.065 0.007" rpy="0 0 0"/>
<geometry>
<box size="0.012 0.132 0.020"/>
</geometry>
</collision>
<!-- This inertial field needs doesn't contain reliable data!! -->
<!-- <inertial>
<mass value="0.564" />
<origin xyz="0 0 0" />
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0"
iyy="0.000498940" iyz="0.0"
izz="0.003879257" />
</inertial>-->
</link>
<joint name="camera_rgb_joint" type="fixed">
<origin xyz="0.005 0.018 0.013" rpy="0 0 0"/>
<!-- <origin xyz="${r200_cam_rgb_px} ${r200_cam_rgb_py} ${r200_cam_rgb_pz}" rpy="0 0 0"/> -->
<parent link="camera_link"/>
<child link="camera_rgb_frame"/>
</joint>
<link name="camera_rgb_frame"/>
<joint name="camera_rgb_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-1.57 0 -1.57"/>
<parent link="camera_rgb_frame"/>
<child link="camera_rgb_optical_frame"/>
</joint>
<link name="camera_rgb_optical_frame"/>
<joint name="camera_depth_joint" type="fixed">
<origin xyz="0.005 0.028 0.013" rpy="-1.57 0 -1.57"/>
<!-- <origin xyz="${r200_cam_rgb_px} ${r200_cam_rgb_py + r200_cam_depth_offset} ${r200_cam_rgb_pz}" rpy="0 0 0"/> -->
<parent link="camera_link"/>
<child link="camera_depth_frame"/>
</joint>
<link name="camera_depth_frame"/>
<joint name="camera_depth_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="camera_depth_frame"/>
<child link="camera_depth_optical_frame"/>
</joint>
<link name="camera_depth_optical_frame"/>
</robot>
......@@ -403,9 +403,7 @@
</collision>
</link>
<link name="camera_link"/>
<link name="camera_rgb_frame">
<link name="camera_link">
<inertial>
<pose>0.069 -0.047 0.107 0 0 0</pose>
<inertia>
......@@ -418,7 +416,6 @@
</inertia>
<mass>0.035</mass>
</inertial>
<collision name="collision">
<pose>0 0.047 0 0 0 0</pose>
<geometry>
......@@ -427,42 +424,35 @@
</box>
</geometry>
</collision>
<pose>0.069 -0.047 0.107 0 0 0</pose>
<sensor name="camera" type="camera">
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>30</update_rate>
<camera name="intel_realsense_r200">
<horizontal_fov>1.02974</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
<sensor name="intel_realsense_r200_depth" type="depth">
<always_on>1</always_on>
<update_rate>5</update_rate>
<pose>0.064 -0.047 0.107 0 0 0</pose>
<camera name="realsense_depth_camera">
</camera>
<plugin name="camera_driver" filename="libgazebo_ros_camera.so">
<ros>
<!-- <namespace>test_cam</namespace> -->
<!-- <argument>image_raw:=image_demo</argument> -->
<!-- <argument>camera_info:=camera_info_demo</argument> -->
</ros>
<!-- camera_name>omit so it defaults to sensor name</camera_name-->
<!-- frame_name>omit so it defaults to link name</frameName-->
<!-- <hack_baseline>0.07</hack_baseline> -->
</plugin>
<plugin name="intel_realsense_r200_depth_driver" filename="libgazebo_ros_camera.so">
<ros>
</ros>
<camera_name>intel_realsense_r200_depth</camera_name>
<frame_name>camera_depth_frame</frame_name>
<hack_baseline>0.07</hack_baseline>
<min_depth>0.001</min_depth>
<max_depth>5.0</max_depth>
</plugin>
</sensor>
<collision name="collision">
<pose>0 0.047 0 0 0 0</pose>
<geometry>
<box>
<size>0.008 0.130 0.022</size>
</box>
</geometry>
</collision>
<pose>0.069 -0.047 0.107 0 0 0</pose>
</link>
<joint name="base_joint" type="fixed">
......
......@@ -86,7 +86,8 @@ Costmap2DROS::Costmap2DROS(
declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
declare_parameter("global_frame", rclcpp::ParameterValue(std::string("map")));
declare_parameter("height", rclcpp::ParameterValue(10));
declare_parameter("height", rclcpp::ParameterValue(5));
declare_parameter("width", rclcpp::ParameterValue(5));
declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
declare_parameter("map_topic", rclcpp::ParameterValue(
(parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map")));
......@@ -106,7 +107,6 @@ Costmap2DROS::Costmap2DROS(
declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
declare_parameter("use_maximum", rclcpp::ParameterValue(false));
declare_parameter("width", rclcpp::ParameterValue(10));
declare_parameter("clearable_layers", rclcpp::ParameterValue(clearable_layers));
}
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment