天天看點

普羅米修斯應該也是可以快速在仿真和真機之間遷移的。

普羅米修斯應該也是可以快速在仿真和真機之間遷移的。

 13:09:07

長遠來看我還是希望自己能跑一跑仿真,仿真和真機的cpp是一樣的

 13:09:08

真機和仿真主要就是launch不同

 13:09:08

是的simulate裡面其實主要也還一些launch

 13:09:09

cpp主體一樣

 13:09:09

launch檔案也主體相同

 13:09:09

能夠快速在仿真和真機中遷移

Simulator檔案夾裡面其實就是一個存放仿真launch檔案的prometheus_gazebo功能包。p450_experiment現在明白可能就是仿照prometheus_gazebo功能包用來存放真機的launch檔案,隻不過移動出去了。

比如這是仿真用的帶航點搜尋的二維碼降落sitl_landing_on_aruco_marker.launch

<launch>
	<!-- Launch Gazebo Simulation -->
	<arg name="x" default="0.0"/>
    <arg name="y" default="0.0"/>
    <arg name="z" default="0.05"/>
	<arg name="world" default="$(find prometheus_gazebo)/worlds/aruco_6X6_250.world"/>
	<arg name="sdf" default="$(find prometheus_gazebo)/amov_models/p450_monocular/p450_monocular.sdf"/>
	<arg name="model" default="p450_monocular"/>
    <include file="$(find prometheus_gazebo)/launch_basic/sitl.launch">
	  <arg name="world" value="$(arg world)"/>
	  <arg name="sdf" value="$(arg sdf)"/>
	  <arg name="model" value="$(arg model)"/>
      <arg name="x" value="$(arg x)"/>
      <arg name="y" value="$(arg y)"/>
      <arg name="z" value="$(arg z)"/>
    </include>

    <!-- 啟動二維碼檢測算法 -->
    <node pkg="prometheus_detection" type="aruco_det" name="aruco_det" output="screen">
		<!-- 相機話題 -->
        <param name="camera_topic" type="string" value="/prometheus/sensor/monocular_down/image_raw" />
		<!-- 相機參數 -->
        <param name="camera_parameters" type="string" value="$(find prometheus_gazebo)/config/camera_config/gimbal_camera.yaml" />
		<!-- 輸出話題1 -->
        <param name="output_pose_topic" type="string" value="/prometheus/object_detection/aruco_det" />
		<!-- 輸出話題2 -->
        <param name="output_multi_pose_topic" type="string" value="/prometheus/object_detection/multi_aruco_det" />
		<!-- 輸出圖像話題 -->
        <param name="output_image_topic" type="string" value="/prometheus/camera/rgb/image_aruco_det" />
		<!-- 10号字典 -->
        <param name="dictionary_type" type="int" value="10" />
		<!-- 指定識别x号marker -->
        <param name="binding_id" type="int" value="19" />
		<!-- marker邊長 10:8 -->
        <param name="target_marker_length" type="double" value="0.4" />
    </node>

	<!-- run the autonomous_landing_aruco.cpp -->
	<node pkg="prometheus_mission" type="autonomous_landing_aruco" name="autonomous_landing_aruco" output="screen" launch-prefix="gnome-terminal --">
		<!-- 仿真模式 - 差別在于是否自動切換offboard模式 -->
		<param name="sim_mode" value="true" />
		<!-- 懸停模式 - 僅用于觀察檢測結果 -->
		<param name="hold_mode" value="false" />
		<!-- 相機安裝偏差 -->
		<param name="camera_offset_x" value="0.0" />
		<param name="camera_offset_y" value="0.0" />
		<param name="camera_offset_z" value="-0.1" />
		<!-- 追蹤控制參數 -->
		<param name="kpx_land" value="0.2" />
		<param name="kpy_land" value="0.2" />
		<param name="kpz_land" value="0.08" />
	</node>

</launch>

           

這是真機用的launch

<launch>
	
 
    <!-- 啟動二維碼檢測算法 -->
    <node pkg="prometheus_detection" type="aruco_det" name="aruco_det" output="screen">
		<!-- 相機話題 -->
        <param name="camera_topic" type="string" value="/prometheus/camera/rgb/image_raw" />
		<!-- 相機參數 -->
        <param name="camera_parameters" type="string" value="$(find prometheus_gazebo)/config/camera_config/gimbal_camera.yaml" />
		<!-- 輸出話題1 -->
        <param name="output_pose_topic" type="string" value="/prometheus/object_detection/aruco_det" />
		<!-- 輸出話題2 -->
        <param name="output_multi_pose_topic" type="string" value="/prometheus/object_detection/multi_aruco_det" />
		<!-- 輸出圖像話題 -->
        <param name="output_image_topic" type="string" value="/prometheus/camera/rgb/image_aruco_det" />
		<!-- 10号字典 -->
        <param name="dictionary_type" type="int" value="10" />
		<!-- 指定識别x号marker -->
        <param name="binding_id" type="int" value="19" />
		<!-- marker邊長 10:8 -->
        <param name="target_marker_length" type="double" value="0.15" />
    </node>
 
	<!-- run the autonomous_landing_aruco.cpp -->
	<node pkg="prometheus_mission" type="autonomous_landing_aruco" name="autonomous_landing_aruco" output="screen" launch-prefix="gnome-terminal --">
		<!-- 仿真模式 - 差別在于是否自動切換offboard模式 -->
		<param name="sim_mode" value="false" />
		<!-- 懸停模式 - 僅用于觀察檢測結果 -->
		<param name="hold_mode" value="false" />
		<!-- 相機安裝偏差 -->
		<param name="camera_offset_x" value="0.0" />
		<param name="camera_offset_y" value="0.0" />
		<param name="camera_offset_z" value="-0.1" />
		<!-- 追蹤控制參數 -->
		<param name="kpx_land" value="0.2" />
		<param name="kpy_land" value="0.2" />
		<param name="kpz_land" value="0.08" />
	</node>
 
</launch>
           

是以隻需要你在仿真中搭建一個和真機一樣的環境,就應該可以快速遷移,就像肖昆打一個無人機比賽一樣。

繼續閱讀