做产品网站费用吗网络推广方案范文
1.按照官网教程安装好ROS+px4
http://dev.px4.io/en/setup/dev_env_linux_ubuntu.html
2.为了确保能加载正确的路径,在.bashrc中增加如下代码。(其中physics是你的用户名)
source /home/physics/src/Firmware/Tools/setup_gazebo.bash /home/physics/src/Firmware /home/physics/src/Firmware/build/px4_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:/home/physics/src/Firmware
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:/home/physics/src/Firmware/Tools/sitl_gazebo
source /usr/share/gazebo-9/setup.sh
export LD_LIBRARY_PATH=${LD_LIBRARY_PATH}:/usr/lib/x86_64-linux-gnu/gazebo-9/plugins/
请注意:px4固件更新之后build目录下的文件夹变成了/px4_sitl_default
3.px4官方world里面有雷达的world,我们在launch文件里面正确加载就可以了
/home/physics/src/Firmware/launch/mavros_posix_sitl.launch
这里主要修改两处地方
修改完成之后roslaunch的时候就能正确加载带有激光雷达的world了
<?xml version="1.0"?>
<launch><param name="/use_sim_time" value="true" /><!-- MAVROS posix SITL environment launch script --><!-- launches MAVROS, PX4 SITL, Gazebo environment, and spawns vehicle --><!-- vehicle pose --><arg name="x" default="0"/><arg name="y" default="0"/><arg name="z" default="0"/><arg name="R" default="0"/><arg name="P" default="0"/><arg name="Y" default="0"/><!-- vehicle model and world --><arg name="est" default="ekf2"/><arg name="vehicle" default="iris_rplidar"/><arg name="world" default="/home/physics/src/Firmware/Tools/sitl_gazebo/worlds/iris_rplidar.world"/><arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
<!--<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/><arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
--><!-- gazebo configs --><arg name="gui" default="true"/><arg name="debug" default="false"/><arg name="verbose" default="false"/><arg name="paused" default="false"/><arg name="respawn_gazebo" default="false"/><!-- MAVROS configs --><arg name="fcu_url" default="udp://:14540@127.0.0.1:14557"/><arg name="respawn_mavros" default="false"/><!-- PX4 configs --><arg name="interactive" default="true"/><!-- PX4 SITL and Gazebo --><include file="$(find px4)/launch/posix_sitl.launch"><arg name="x" value="$(arg x)"/><arg name="y" value="$(arg y)"/><arg name="z" value="$(arg z)"/><arg name="R" value="$(arg R)"/><arg name="P" value="$(arg P)"/><arg name="Y" value="$(arg Y)"/><arg name="world" value="$(arg world)"/><arg name="vehicle" value="$(arg vehicle)"/><arg name="sdf" value="$(arg sdf)"/><arg name="gui" value="$(arg gui)"/><arg name="interactive" value="$(arg interactive)"/><arg name="debug" value="$(arg debug)"/><arg name="verbose" value="$(arg verbose)"/><arg name="paused" value="$(arg paused)"/><arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/></include><!-- MAVROS --><include file="$(find mavros)/launch/px4.launch"><!-- GCS link is provided by SITL --><arg name="gcs_url" value=""/><arg name="fcu_url" value="$(arg fcu_url)"/><arg name="respawn_mavros" value="$(arg respawn_mavros)"/></include>
</launch>
4.我这里使用的建图算法是cartographer,如果要接入虚拟的激光雷达进行建图还需要修改坐标系名字以便于后面tf变换正确
/home/physics/src/Firmware/Tools/sitl_gazebo/models/rplidar/model.sdf
主要修改上面两行,其实关于整个雷达的描述以及配置最后构建的时候都是调用这个文件的,我们可以在这里修改我们需要的参数
<?xml version="1.0" ?>
<sdf version="1.5"><model name="rplidar"><link name="link"><inertial><pose>0 0 0 0 0 0</pose><mass>0.19</mass><inertia><ixx>4.15e-6</ixx><ixy>0</ixy><ixz>0</ixz><iyy>2.407e-6</iyy><iyz>0</iyz><izz>2.407e-6</izz></inertia></inertial><visual name="visual"><geometry><box><size>0.02 0.05 0.05</size></box></geometry></visual><sensor name="laser" type="gpu_ray"><ray><scan><horizontal><samples>360</samples><resolution>1</resolution><min_angle>-3.14</min_angle><max_angle>3.14</max_angle></horizontal></scan><range><min>0.2</min><max>6</max><resolution>0.05</resolution></range><noise><type>gaussian</type><mean>0.0</mean><stddev>0.01</stddev></noise></ray><plugin name="laser" filename="libGpuRayPlugin.so" /><plugin name="gazebo_ros_head_rplidar_controller" filename="libgazebo_ros_gpu_laser.so"><topicName>/scan</topicName><frameName>laser</frameName></plugin><always_on>1</always_on><update_rate>10</update_rate><visualize>true</visualize></sensor></link></model>
</sdf><!-- vim: set et fenc= ff=unix sts=0 sw=2 ts=2 : -->
/home/physics/catkin_ws/src/cartographer_ros/cartographer_ros/launch/cartographer.launch
这里主要修改一个地方,就是增加一个param,不然建图的时候会得不到正确的时间
<?xml version="1.0"?><launch><param name="/use_sim_time" value="true" /><node name="cartographer_node"pkg="cartographer_ros"type="cartographer_node"args="-configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename cartographer.lua"output="screen"></node><node name="cartographer_occupancy_grid_node"pkg="cartographer_ros"type="cartographer_occupancy_grid_node" /><node name="robot_pose_publisher"pkg="robot_pose_publisher"type="robot_pose_publisher"respawn="false"output="screen" /><node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 base_link laser 100" /><node name="rviz"pkg="rviz" type="rviz" required="true"args="-d $(find cartographer_ros)/configuration_files/cartographer_2d.rviz" /></launch>
/home/physics/catkin_ws/src/cartographer_ros/cartographer_ros/configuration_files/cartographer.lua
这里也是增加几个参数:
修改好之后如下:
include "map_builder.lua"
include "trajectory_builder.lua"options = {map_builder = MAP_BUILDER,trajectory_builder = TRAJECTORY_BUILDER,map_frame = "map",tracking_frame = "base_link",published_frame = "base_link",odom_frame = "odom",provide_odom_frame = true,use_odometry = false,use_nav_sat = false,use_landmarks = false,publish_frame_projected_to_2d = false,num_laser_scans = 1,num_multi_echo_laser_scans = 0,num_subdivisions_per_laser_scan = 1,rangefinder_sampling_ratio = 1,odometry_sampling_ratio = 1,fixed_frame_pose_sampling_ratio = 1,imu_sampling_ratio = 1,landmarks_sampling_ratio = 1,num_point_clouds = 0,lookup_transform_timeout_sec = 0.2,submap_publish_period_sec = 0.3,pose_publish_period_sec = 5e-3,trajectory_publish_period_sec = 30e-3,
}MAP_BUILDER.use_trajectory_builder_2d = trueTRAJECTORY_BUILDER_2D.use_imu_data = falseTRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = truePOSE_GRAPH.optimization_problem.huber_scale = 1e2TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10return options
5.启动
roslaunch px4 mavros_posix_sitl.launch
rosrun offb offb_node
roslaunch cartographer_ros cartographer.launch
roslaunch px4_navigation px4_nav.launch
因为整个系统工程涉及模块较多,这这里难以一一展开记录等整个工程完成,会整理上传到github