Skip to content
GitLab
Menu
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
U2IS
husky-ensta
Commits
5e32a0b0
Unverified
Commit
5e32a0b0
authored
May 11, 2020
by
Simon Thomas
Browse files
Adding corresponding naviagation parameters
parent
09d001a6
Changes
3
Hide whitespace changes
Inline
Side-by-side
husky_gazebo/launch/spawn_husky.launch
View file @
5e32a0b0
...
@@ -36,18 +36,18 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
...
@@ -36,18 +36,18 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<arg
name=
"laser_enabled"
default=
"$(optenv HUSKY_LMS1XX_ENABLED false)"
/>
<arg
name=
"laser_enabled"
default=
"$(optenv HUSKY_LMS1XX_ENABLED false)"
/>
<arg
name=
"kinect_enabled"
default=
"$(optenv HUSKY_UR5_ENABLED false)"
/>
<arg
name=
"kinect_enabled"
default=
"$(optenv HUSKY_UR5_ENABLED false)"
/>
<arg
name=
"urdf_extras"
default=
"$(optenv HUSKY_URDF_EXTRAS)"
/>
<
!--
arg name="urdf_extras" default="$(optenv HUSKY_URDF_EXTRAS)"/>
-->
<group
ns=
"$(arg robot_namespace)"
>
<group
ns=
"$(arg robot_namespace)"
>
<group
if=
"$(arg multimaster)"
>
<include
file=
"$(find husky_description)/launch/description.launch"
>
<include
file=
"$(find husky_description)/launch/description.launch"
>
<arg
name=
"robot_namespace"
value=
"$(arg robot_namespace)"
/>
<arg
name=
"robot_namespace"
value=
"$(arg robot_namespace)"
/>
<arg
name=
"laser_enabled"
default=
"$(arg laser_enabled)"
/>
<arg
name=
"laser_enabled"
default=
"$(arg laser_enabled)"
/>
<arg
name=
"kinect_enabled"
default=
"$(arg kinect_enabled)"
/>
<arg
name=
"kinect_enabled"
default=
"$(arg kinect_enabled)"
/>
<arg
name=
"urdf_extras"
default=
"$(arg urdf_extras)"
/>
<!--
<arg name="urdf_extras" default="$(arg urdf_extras)"/>
-->
</include>
</include>
<group
if=
"$(arg multimaster)"
>
<include
file=
"$(find multimaster_launch)/launch/multimaster_gazebo_robot.launch"
>
<include
file=
"$(find multimaster_launch)/launch/multimaster_gazebo_robot.launch"
>
<arg
name=
"gazebo_interface"
value=
"$(find husky_control)/config/gazebo_interface.yaml"
/>
<arg
name=
"gazebo_interface"
value=
"$(find husky_control)/config/gazebo_interface.yaml"
/>
<arg
name=
"robot_namespace"
value=
"$(arg robot_namespace)"
/>
<arg
name=
"robot_namespace"
value=
"$(arg robot_namespace)"
/>
...
@@ -64,7 +64,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
...
@@ -64,7 +64,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<arg
name=
"multimaster"
value=
"$(arg multimaster)"
/>
<arg
name=
"multimaster"
value=
"$(arg multimaster)"
/>
<arg
name=
"laser_enabled"
value=
"$(arg laser_enabled)"
/>
<arg
name=
"laser_enabled"
value=
"$(arg laser_enabled)"
/>
<arg
name=
"kinect_enabled"
value=
"$(arg kinect_enabled)"
/>
<arg
name=
"kinect_enabled"
value=
"$(arg kinect_enabled)"
/>
<
arg
name=
"urdf_extras"
value=
"$(arg urdf_extras)"
/>
<!--
arg name="urdf_extras" value="$(arg urdf_extras)"/>
-->
</include>
</include>
</group>
</group>
...
...
husky_navigation/config/costmap_common.yaml
View file @
5e32a0b0
...
@@ -13,12 +13,12 @@ raytrace_range: 6.0
...
@@ -13,12 +13,12 @@ raytrace_range: 6.0
#layer definitions
#layer definitions
static
:
static
:
map_topic
:
/map
map_topic
:
/
rtabmap/grid_
map
subscribe_to_updates
:
true
subscribe_to_updates
:
true
obstacles_laser
:
obstacles_laser
:
observation_sources
:
laser
observation_sources
:
robosense zed
laser
:
{
data_type
:
LaserScan
,
clearing
:
true
,
marking
:
true
,
topic
:
scan
,
inf_is_valid
:
true
}
robosense
:
{
sensor_frame
:
robosense
,
data_type
:
PointCloud2
,
topic
:
rs_points
,
marking
:
true
,
clearing
:
true
}
zed
:
{
sensor_frame
:
zed_optical_frame
,
data_type
:
PointCloud2
,
topic
:
zed/depth/points
,
marking
:
true
,
clearing
:
true
}
inflation
:
inflation
:
inflation_radius
:
1.0
inflation_radius
:
1.0
husky_navigation/config/planner.yaml
View file @
5e32a0b0
...
@@ -13,12 +13,12 @@ TrajectoryPlannerROS:
...
@@ -13,12 +13,12 @@ TrajectoryPlannerROS:
max_vel_x
:
1.0
max_vel_x
:
1.0
min_vel_x
:
0.0
min_vel_x
:
0.0
max_vel_theta
:
1.0
max_vel_theta
:
0.5
min_vel_theta
:
-
1.0
min_vel_theta
:
-
0.5
min_in_place_vel_theta
:
0.
2
min_in_place_vel_theta
:
0.
4
holonomic_robot
:
false
holonomic_robot
:
false
escape_vel
:
-0.
1
escape_vel
:
-0.
3
# Goal Tolerance Parameters
# Goal Tolerance Parameters
yaw_goal_tolerance
:
0.1
yaw_goal_tolerance
:
0.1
...
@@ -64,7 +64,7 @@ DWAPlannerROS:
...
@@ -64,7 +64,7 @@ DWAPlannerROS:
max_trans_vel
:
0.5
max_trans_vel
:
0.5
min_trans_vel
:
0.1
min_trans_vel
:
0.1
max_rot_vel
:
1.0
max_rot_vel
:
0.5
min_rot_vel
:
0.2
min_rot_vel
:
0.2
# Goal Tolerance Parameters
# Goal Tolerance Parameters
...
@@ -90,4 +90,4 @@ DWAPlannerROS:
...
@@ -90,4 +90,4 @@ DWAPlannerROS:
# max_scaling_factor: 0.2 # The maximum factor to scale the robot's footprint by
# max_scaling_factor: 0.2 # The maximum factor to scale the robot's footprint by
# # Oscillation Prevention Parameters
# # Oscillation Prevention Parameters
# oscillation_reset_dist: 0.25 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)
# oscillation_reset_dist: 0.25 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)
\ No newline at end of file
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment