modify param for ego_planner
This commit is contained in:
parent
8779f9c558
commit
250f0e8e66
|
@ -94,7 +94,7 @@
|
|||
<param name="grid_map/local_update_range_z" value="4.5" />
|
||||
<param name="grid_map/obstacles_inflation" value="0.2" />
|
||||
<param name="grid_map/local_map_margin" value="10"/>
|
||||
<param name="grid_map/ground_height" value="0.24"/>
|
||||
<param name="grid_map/ground_height" value="-1"/>
|
||||
<!-- camera parameter -->
|
||||
<param name="grid_map/cx" value="$(arg cx)"/>
|
||||
<param name="grid_map/cy" value="$(arg cy)"/>
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
<launch>
|
||||
<arg name="map_size_x" value="20.0"/>
|
||||
<arg name="map_size_y" value="20.0"/>
|
||||
<arg name="map_size_z" value=" 3.0"/>
|
||||
<arg name="map_size_x" value="100"/>
|
||||
<arg name="map_size_y" value="100"/>
|
||||
<arg name="map_size_z" value=" 5"/>
|
||||
|
||||
<arg name="odom_topic" value="vins_estimator/odometry" />
|
||||
|
||||
|
|
|
@ -23,7 +23,7 @@ def vision_callback(data):
|
|||
local_pose.pose.orientation.y = q_[2]
|
||||
local_pose.pose.orientation.z = q_[3]
|
||||
|
||||
rospy.init_node(vehicle_type+"_"+vehicle_id+'/ego_transfer')
|
||||
rospy.init_node(vehicle_type+"_"+vehicle_id+'_ego_transfer')
|
||||
rospy.Subscriber(vehicle_type+"_"+vehicle_id+"/mavros/vision_pose/pose", PoseStamped, vision_callback)
|
||||
position_pub = rospy.Publisher(vehicle_type+"_"+vehicle_id+"/camera_pose", PoseStamped, queue_size=2)
|
||||
rate = rospy.Rate(60)
|
||||
|
|
Loading…
Reference in New Issue