Browse Source

新增在启动robot_bringup时启动get_battery.launch

corvin rasp melodic 2 years ago
parent
commit
fc700c52ac

+ 1 - 1
src/oled_screen/src/main.cpp

@@ -31,7 +31,7 @@ int main()
         // int battery = battery_dev.I2C_Read_Battery();
         std::string bat_percent = std::to_string(battery_dev.I2C_Read_Battery()) + "%";
         oled_driver.GUI_Show(bat_percent);
-		sleep(20);
+        sleep(20);
 	}
     //3.System Exit
 	Device::DEV_ModuleExit();

+ 12 - 13
src/robot_bringup/CMakeLists.txt

@@ -2,12 +2,16 @@ cmake_minimum_required(VERSION 2.8.3)
 project(robot_bringup)
 
 ## Compile as C++11, supported in ROS Kinetic and newer
-# add_compile_options(-std=c++11)
+add_compile_options(-std=c++11)
 
 ## Find catkin macros and libraries
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
 ## is used, also find other catkin packages
-find_package(catkin REQUIRED)
+find_package(catkin REQUIRED
+    roscpp
+    ros_arduino_msgs
+    std_msgs
+    )
 
 ## System dependencies are found with CMake's conventions
 # find_package(Boost REQUIRED COMPONENTS system)
@@ -36,14 +40,9 @@ catkin_package(
 ## Your package locations should be listed before other locations
 include_directories(
 # include
-# ${catkin_INCLUDE_DIRS}
+  ${catkin_INCLUDE_DIRS}
 )
 
-## Declare a C++ library
-# add_library(${PROJECT_NAME}
-#   src/${PROJECT_NAME}/robot_bringup.cpp
-# )
-
 ## Add cmake target dependencies of the library
 ## as an example, code may need to be generated before libraries
 ## either from message generation or dynamic reconfigure
@@ -52,7 +51,7 @@ include_directories(
 ## Declare a C++ executable
 ## With catkin_make all packages are built within a single CMake context
 ## The recommended prefix ensures that target names across packages don't collide
-# add_executable(${PROJECT_NAME}_node src/robot_bringup_node.cpp)
+add_executable(get_battery_node src/get_battery.cpp)
 
 ## Rename C++ executable without prefix
 ## The above recommended prefix causes long target names, the following renames the
@@ -62,12 +61,12 @@ include_directories(
 
 ## Add cmake target dependencies of the executable
 ## same as for the library above
-# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+add_dependencies(get_battery_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
 
 ## Specify libraries to link a library or executable target against
-# target_link_libraries(${PROJECT_NAME}_node
-#   ${catkin_LIBRARIES}
-# )
+target_link_libraries(get_battery_node
+  ${catkin_LIBRARIES}
+)
 
 #############
 ## Install ##

+ 4 - 0
src/robot_bringup/launch/get_battery.launch

@@ -0,0 +1,4 @@
+<launch>
+    <node pkg="robot_bringup" type="get_battery_node" name="get_battery_node" output="screen">
+    </node>
+</launch>

+ 4 - 0
src/robot_bringup/launch/robot_bringup.launch

@@ -9,6 +9,7 @@
   History:
     20200716:init this file.
     20210602:使用串口获取imu模块的数据.
+    20220902:增加启动oled显示屏的launch.
 -->
 <launch>
     <!-- (1) startup panda robot urdf description -->
@@ -40,5 +41,8 @@
         <remap from="input" to="/robot_pose_ekf/odom_combined" />
         <remap from="output" to="/odom_ekf" />
     </node>
+
+    <!-- (7) startup get battery oled show -->
+    <include file="$(find robot_bringup)/launch/get_battery.launch"/>
 </launch>
 

+ 7 - 2
src/robot_bringup/package.xml

@@ -14,8 +14,13 @@
   <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
   <license>TODO</license>
   <buildtool_depend>catkin</buildtool_depend>
-  <!-- The export tag contains other, unspecified, tags -->
+  <build_depend>ros_arduino_msgs</build_depend>
+  <build_depend>roscpp</build_depend>
+  <build_export_depend>ros_arduino_msgs</build_export_depend>
+  <build_export_depend>roscpp</build_export_depend>
+  <exec_depend>ros_arduino_msgs</exec_depend>
+  <exec_depend>roscpp</exec_depend>
+
   <export>
-    <!-- Other tools can request additional information be placed here -->
   </export>
 </package>

+ 27 - 0
src/robot_bringup/src/get_battery.cpp

@@ -0,0 +1,27 @@
+/*
+ * @Author: adam_zhuo
+ * @Date: 2022-07-09 14:10:00
+ * @Description: Init this file.
+ * @History: 20210429:-adam_zhuo
+*/
+#include <ros/ros.h>
+#include "ros_arduino_msgs/Digital.h"
+#include <fstream>
+#include <iostream>
+
+void battery_callback(const ros_arduino_msgs::Digital::ConstPtr& msg)
+{
+    std::ofstream bat_file;
+    bat_file.open("/home/corvin/.bat", std::ios::out);
+    bat_file << int(msg->value);
+    bat_file.close();
+}
+
+int main(int argc, char **argv)
+{
+    ros::init(argc, argv, "get_battery_node");
+    ros::NodeHandle handle;
+    ros::Subscriber sub_battey = handle.subscribe("/mobilebase_arduino/sensor/batPercent", 1, battery_callback);
+    ros::spin();
+    return 0;
+}

+ 6 - 25
src/robot_navigation/README.md

@@ -2,46 +2,27 @@
 建图导航功能包,可实现建图导航功能
 
 ### 建图运行方法
-首先启动小车
+运行建图程序gmapping
 
 ```sh
-$ roslaunch robot_bringup robot_bringup.launch
+$ roslaunch robot_navigation gmapping.launch
 ```
 
-然后运行键盘控制程序
+然后运行键盘控制程序,用键盘控制小车移动可建立地图地图
 
 ```sh
 $ rosrun control_robot control_robot.py
 ```
 
-再运行建图程序gmapping
-
-```sh
-$ roslaunch robot_navigation gmapping_ydlidar_X2L.launch
-```
-
-启动rviz可视化工具
-
-```sh
-$ roslaunch robot_navigation view_navigation.launch
-```
-用键盘控制小车移动可建立地图地图
-
 最后保存地图
 
 ```sh
-$ rosrun map_server map_saver -f  ~/panda_ws/src/robot_navigation/maps/mymap
+$ rosrun map_server map_saver -f  ~/panda_ws/src/robot_navigation/maps/test_map
 ```
 
 ### 导航运行方法
-首先启动小车,运行amcl导航
-
-```sh
-$ roslaunch robot_navigation amcl_ydlidar_X2L.launch
-```
-
-启动rviz可视化工具
+运行amcl导航
 
 ```sh
-$ roslaunch robot_navigation view_navigation.launch
+$ roslaunch robot_navigation amcl_dwa.launch
 ```

+ 1 - 0
src/robot_navigation/config/teb_cfg/amcl_params.yaml

@@ -39,3 +39,4 @@ resample_interval: 1
 transform_tolerance: 3
 recovery_alpha_slow: 0.0
 recovery_alpha_fast: 0.0
+

+ 3 - 4
src/robot_navigation/config/teb_cfg/costmap_converter_params.yaml

@@ -7,15 +7,14 @@
 
 TebLocalPlannerROS:
 
-  ## Costmap converter plugin   
+  ## Costmap converter plugin
   #costmap_converter_plugin: "costmap_converter::CostmapToPolygonsDBSMCCH"
   costmap_converter_plugin: "costmap_converter::CostmapToLinesDBSRANSAC"
   #costmap_converter_plugin: "costmap_converter::CostmapToLinesDBSMCCH"
   #costmap_converter_plugin: "costmap_converter::CostmapToPolygonsDBSConcaveHull"
   costmap_converter_spin_thread: True
   costmap_converter_rate: 5
- 
- 
+
   ## Configure plugins (namespace move_base/costmap_to_lines or move_base/costmap_to_polygons)
   ## costmap_converter/CostmapToLinesDBSRANSAC, costmap_converter/CostmapToLinesDBSMCCH, costmap_converter/CostmapToPolygonsDBSMCCH
   costmap_converter/CostmapToLinesDBSRANSAC:
@@ -28,4 +27,4 @@ TebLocalPlannerROS:
     ransac_convert_outlier_pts: True
     ransac_filter_remaining_outlier_pts: False
     convex_hull_min_pt_separation: 0.1
- 
+

+ 7 - 14
src/robot_navigation/config/teb_cfg/teb_local_planner_params.yaml

@@ -3,7 +3,6 @@ TebLocalPlannerROS:
  odom_topic: odom_ekf
     
  # Trajectory
-  
  teb_autosize: True
  dt_ref: 0.3
  dt_hysteresis: 0.1
@@ -16,29 +15,26 @@ TebLocalPlannerROS:
  exact_arc_length: False
  feasibility_check_no_poses: 5
  publish_feedback: False
-    
+
  # Robot
-         
- max_vel_x: 0.7
+ max_vel_x: 0.8
  max_vel_x_backwards: 0.2
  max_vel_y: 0.0
  max_vel_theta: 2.0
  acc_lim_x: 0.5
  acc_lim_theta: 1.1
- min_turning_radius: 0.0 # diff-drive robot (can turn on place!)
+ min_turning_radius: 0.0 #diff-drive robot (can turn on place!)
 
  footprint_model:
    type: "point"
 
  # GoalTolerance
-    
- xy_goal_tolerance: 0.75
- yaw_goal_tolerance: 0.8
+ xy_goal_tolerance: 0.5
+ yaw_goal_tolerance: 0.5
  free_goal_vel: False
  complete_global_plan: True
-    
+
  # Obstacles
-    
  min_obstacle_dist: 0.15 # This value must also include our robot radius, since footprint_model is set to "point".
  inflation_dist: 0.6
  include_costmap_obstacles: True
@@ -53,7 +49,6 @@ TebLocalPlannerROS:
  costmap_converter_rate: 5
 
  # Optimization
-    
  no_inner_iterations: 5
  no_outer_iterations: 4
  optimization_activate: True
@@ -67,7 +62,7 @@ TebLocalPlannerROS:
  weight_kinematics_nh: 1000
  weight_kinematics_forward_drive: 1
  weight_kinematics_turning_radius: 1
- weight_optimaltime: 4 # must be > 0
+ weight_optimaltime: 4  # must be > 0
  weight_shortest_path: 0
  weight_obstacle: 100
  weight_inflation: 0.2
@@ -77,7 +72,6 @@ TebLocalPlannerROS:
  weight_adapt_factor: 2
 
  # Homotopy Class Planner
-
  enable_homotopy_class_planning: True
  enable_multithreading: True
  max_number_classes: 4
@@ -100,7 +94,6 @@ TebLocalPlannerROS:
  visualize_with_time_as_z_axis_scale: False
 
 # Recovery
- 
  shrink_horizon_backup: True
  shrink_horizon_min_duration: 10
  oscillation_recovery: True

+ 16 - 11
src/robot_navigation/launch/amcl_teb.launch

@@ -1,31 +1,36 @@
 <launch>
-    <include file="$(find robot_bringup)/launch/robot_bringup.launch" />
+    <!-- startup robot_bringup -->
+    <include file="$(find robot_bringup)/launch/robot_bringup.launch"/>
 
-    <!--  ****** Maps *****  -->
-	<node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/test_map.yaml" output="screen" />
+    <!-- load navigation map -->
+    <node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/test_map.yaml" output="screen" />
 
-    <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
+   <!-- startup EAI X2L lidar -->
+    <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch"/>
 
-    <!--  ************** Navigation ***************  -->
+    <!-- startup Navigation -->
 	<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
-  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/costmap_common_params.yaml" command="load" ns="global_costmap" />
-  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/costmap_common_params.yaml" command="load" ns="local_costmap" />
+  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/costmap_common_params.yaml" command="load" ns="global_costmap"/>
+  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/costmap_common_params.yaml" command="load" ns="local_costmap"/>
   	  <rosparam file="$(find robot_navigation)/config/teb_cfg/local_costmap_params.yaml" command="load" />
   	  <rosparam file="$(find robot_navigation)/config/teb_cfg/global_costmap_params.yaml" command="load" />
   	  <rosparam file="$(find robot_navigation)/config/teb_cfg/teb_local_planner_params.yaml" command="load" />
       <rosparam file="$(find robot_navigation)/config/teb_cfg/base_global_planner_params.yaml" command="load" />
 
 	  <param name="base_global_planner" value="global_planner/GlobalPlanner" />
-	  <param name="planner_frequency" value="1.0" />
-	  <param name="planner_patience" value="5.0" />
+	  <param name="planner_frequency"   value="1.0" />
+	  <param name="planner_patience"    value="5.0" />
 
-	  <param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
+	  <param name="base_local_planner"   value="teb_local_planner/TebLocalPlannerROS" />
 	  <param name="controller_frequency" value="15.0" />
-	  <param name="controller_patience" value="15.0" />
+	  <param name="controller_patience"  value="15.0" />
 	</node>
 
 	<node pkg="amcl" type="amcl" name="amcl" output="screen">
 	    <rosparam file="$(find robot_navigation)/config/teb_cfg/amcl_params.yaml" command="load" />
 	</node>
+
+    <!-- startup view_navigation.launch -->
+    <include file="$(find robot_navigation)/launch/view_navigation.launch" />
 </launch>