modify the mpi scripts
This commit is contained in:
parent
d29ad9c571
commit
6f1434a43f
|
@ -1,13 +1,16 @@
|
|||
#!/bin/bash
|
||||
#########################################################################
|
||||
# Author: Zhang Shuai #
|
||||
# Date: 2019-05-23 #
|
||||
# Description: launch a MPI Gazebo simulation task #
|
||||
# Usage: ./MPI_Gazebo_launch.sh [hostfile] [world's path and name] #
|
||||
#########################################################################
|
||||
#####################################################################################################################################
|
||||
# Author: Zhang Shuai #
|
||||
# Date: 2019-05-23 #
|
||||
# Description: launch a MPI Gazebo simulation task #
|
||||
# Usage: ./MPI_Gazebo_launch.sh [ros packdge's name] [launch file's name] [workspace's path] [world's path and name] [hostfile] #
|
||||
#####################################################################################################################################
|
||||
|
||||
host_file=$1
|
||||
world_file=$2
|
||||
packdge_name=$1
|
||||
launch_file_name=$2
|
||||
workspace_path=$3
|
||||
world_file=$4
|
||||
host_file=$5
|
||||
|
||||
host_count=0
|
||||
hosts=()
|
||||
|
@ -33,7 +36,7 @@ done
|
|||
#登入各节点启动roscore (source还有改进空间,ROS运行的工作目录应该作为参数传进来)
|
||||
for((i=0;i<host_count;i++))
|
||||
do
|
||||
ssh -f -n ${hosts[$i]} "source ~/catkin_ws/devel/setup.bash;
|
||||
ssh -f -n ${hosts[$i]} "source $workspace_path/devel/setup.bash;
|
||||
roscore;
|
||||
echo roscore_done!"
|
||||
echo "${hosts[$i]}:roscore_good"
|
||||
|
@ -43,7 +46,7 @@ sleep 5s
|
|||
|
||||
#登入第一个节点启动MPI的gzserver,并成为各自节点上的ROS node
|
||||
ssh -f -n ${hosts[0]} "cd ~/MPI;
|
||||
mpiexec -hostfile hostfile -np 1 mygzserver $world_file : -np 1 mygzserver $world_file;
|
||||
mpiexec -hostfile $host_file -np 1 mygzserver $world_file $workspace_path : -np 1 mygzserver $world_file $workspace_path;
|
||||
echo mpiexec_done!"
|
||||
echo "${hosts[0]}:mpiexec_good"
|
||||
|
||||
|
@ -52,8 +55,8 @@ sleep 20s
|
|||
#登入各节点roslaunch加载模型(source还有改进空间,ROS运行的工作目录应该作为参数传进来)
|
||||
for((i=0;i<host_count;i++))
|
||||
do
|
||||
ssh -f -n ${hosts[$i]} "source ~/catkin_ws/devel/setup.bash;
|
||||
roslaunch hector_quadrotor_gazebo hector_2_single_gazebo_mpi_spawn_test.launch;
|
||||
ssh -f -n ${hosts[$i]} "source $workspace_path/devel/setup.bash;
|
||||
roslaunch $packdge_name $launch_file_name;
|
||||
echo roslaunch_done!"
|
||||
echo "${hosts[$i]}:roslaunch_good"
|
||||
done
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
#echo ++++++++$1
|
||||
source /opt/ros/kinetic/setup.bash
|
||||
source ~/catkin_ws/devel/setup.bash
|
||||
source $2/devel/setup.bash
|
||||
|
||||
export DISPLAY=:0.0
|
||||
|
||||
|
|
|
@ -0,0 +1,30 @@
|
|||
<!-- This is a launch file that runs the bare minimum requirements to get -->
|
||||
<!-- gazebo running for a fixed-wing aircraft -->
|
||||
|
||||
<launch>
|
||||
|
||||
<group ns="bebop_0">
|
||||
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||
<arg name="name" value="bebop_0" />
|
||||
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||
<arg name="tf_prefix" value="bebop_0" />
|
||||
<arg name="x" value="0.0" />
|
||||
<arg name="y" value="0.0" />
|
||||
<arg name="z" value="0.186" />
|
||||
</include>
|
||||
</group>
|
||||
|
||||
<group ns="bebop_1">
|
||||
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||
<arg name="name" value="bebop_1" />
|
||||
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||
<arg name="tf_prefix" value="bebop_1" />
|
||||
<arg name="x" value="0.0" />
|
||||
<arg name="y" value="5.0" />
|
||||
<arg name="z" value="0.186" />
|
||||
</include>
|
||||
</group>
|
||||
|
||||
<node name="simple_takeoff" pkg="hector" type="hector_simple_takeoff"/>
|
||||
|
||||
</launch>
|
Loading…
Reference in New Issue