Skip to content

Commit

Permalink
remove unncessary slashes, reduce default speed
Browse files Browse the repository at this point in the history
  • Loading branch information
ldg810 committed Aug 25, 2020
1 parent 64331f1 commit 05f53b9
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion global_planner/launch/global_planner_depth-camera.launch
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<!-- Global planner -->
<include file="$(find global_planner)/launch/global_planner_octomap.launch" >
<arg name="pointcloud_topics" value="$(arg pointcloud_topics)" />
<arg name="camera_frame_id" value="/$(arg camera_frame_id)" />
<arg name="camera_frame_id" value="$(arg camera_frame_id)" />
<arg name="start_pos_x" value="$(arg start_pos_x)" />
<arg name="start_pos_y" value="$(arg start_pos_y)" />
<arg name="start_pos_z" value="$(arg start_pos_z)" />
Expand Down
2 changes: 1 addition & 1 deletion global_planner/launch/global_planner_octomap.launch
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
<node name="global_planner_node" pkg="global_planner" type="global_planner_node" output="screen"
args="$(find global_planner)/resource/random_goals" >
<param name="frame_id" type="string" value="$(arg frame_id)" />
<param name="camera_frame_id" type="string" value="$(arg camera_frame_id)" />
<param name="camera_frame_id" type="string" value="/$(arg camera_frame_id)" />
<param name="start_pos_x" value="$(arg start_pos_x)" />
<param name="start_pos_y" value="$(arg start_pos_y)" />
<param name="start_pos_z" value="$(arg start_pos_z)" />
Expand Down
2 changes: 1 addition & 1 deletion global_planner/launch/global_planner_sitl_3cam.launch
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
<arg name="start_pos_y" value="$(arg start_pos_y)" />
<arg name="start_pos_z" value="$(arg start_pos_z)" />
<arg name="pointcloud_topics" value="$(arg pointcloud_topics)"/>
<arg name="camera_frame_id" value="/$(arg camera_frame_id)" />
<arg name="camera_frame_id" value="$(arg camera_frame_id)" />
</include>

<!-- RViz -->
Expand Down
2 changes: 1 addition & 1 deletion global_planner/src/nodes/global_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ GlobalPlannerNode::GlobalPlannerNode(const ros::NodeHandle& nh, const ros::NodeH
current_goal_.pose.orientation = tf::createQuaternionMsgFromYaw(start_yaw_);
last_goal_ = current_goal_;

speed_ = 5.0;
speed_ = 2.0;

start_time_ = ros::Time::now();
}
Expand Down

0 comments on commit 05f53b9

Please sign in to comment.