start.bash
This commit is contained in:
parent
0b65c73c34
commit
ef45a0d522
@ -24,10 +24,19 @@ diff_cont:
|
||||
|
||||
linear:
|
||||
x:
|
||||
has_velocity_limits: true
|
||||
max_velocity: 0.5
|
||||
has_velocity_limits : true
|
||||
max_velocity : 1.0 # m/s
|
||||
min_velocity : -0.5 # m/s
|
||||
has_acceleration_limits: true
|
||||
max_acceleration: 0.2
|
||||
max_acceleration : 0.6 # m/s^2
|
||||
min_acceleration : -0.3 # m/s^2
|
||||
angular:
|
||||
z:
|
||||
has_velocity_limits : true
|
||||
max_velocity : 1.0 # rad/s
|
||||
has_acceleration_limits: true
|
||||
max_acceleration : 0.8 # rad/s^2
|
||||
|
||||
|
||||
joint_limits:
|
||||
ros__parameters:
|
||||
|
@ -8,6 +8,7 @@ declare -a windows=(
|
||||
"base"
|
||||
"remote_control"
|
||||
"lidar"
|
||||
# "slam"
|
||||
"nav2"
|
||||
)
|
||||
declare -a work_dirs=(
|
||||
@ -15,16 +16,16 @@ declare -a work_dirs=(
|
||||
$DCAITI_PATH
|
||||
$DCAITI_PATH/src/dcaitirobot/launch
|
||||
$DCAITI_PATH
|
||||
$DCAITI_PATH/src/dcaitirobot/launch
|
||||
#$DCAITI_PATH/src/dcaiti_navigation/launch
|
||||
# $DCAITI_PATH/src/dcaitirobot/launch
|
||||
$DCAITI_PATH/src/dcaiti_navigation/launch
|
||||
)
|
||||
declare -a commands=(
|
||||
"htop"
|
||||
"ros2 launch dcaiti_control launch_robot.py"
|
||||
"ros2 launch remote_control_launch.py"
|
||||
"ros2 launch velodyne velodyne-all-nodes-VLP16-launch.py"
|
||||
"ros2 launch launch_slam.py"
|
||||
#"ros2 launch start_nav2.py"
|
||||
# "ros2 launch launch_slam.py"
|
||||
"ros2 launch start_nav2.py"
|
||||
)
|
||||
|
||||
# Start tmux
|
||||
|
Loading…
x
Reference in New Issue
Block a user