Browse Source

新增运动控制和语音demo

adam_zhuo 3 years ago
parent
commit
58fee02923

+ 8 - 2
src/robot_demo/CMakeLists.txt

@@ -143,8 +143,9 @@ add_executable(${PROJECT_NAME}_color_node
               src/kalman_filter.cpp)
 
 add_executable(${PROJECT_NAME}_imu_node src/imu_demo_node.cpp)
-add_executable(${PROJECT_NAME}_infrared_node src/infrared_demo.cpp)
-add_executable(${PROJECT_NAME}_voice_node src/voice_demo.cpp)
+add_executable(${PROJECT_NAME}_infrared_node src/infrared_demo_node.cpp)
+add_executable(${PROJECT_NAME}_voice_node src/voice_demo_node.cpp)
+add_executable(${PROJECT_NAME}_motion_control_node src/motion_control_demo_node.cpp)
 
 
 ## Rename C++ executable without prefix
@@ -157,6 +158,7 @@ add_executable(${PROJECT_NAME}_voice_node src/voice_demo.cpp)
 ## same as for the library above
 # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
 add_dependencies(${PROJECT_NAME}_infrared_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}_motion_control_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
 
 ## Specify libraries to link a library or executable target against
 # target_link_libraries(${PROJECT_NAME}_node
@@ -179,6 +181,10 @@ target_link_libraries(${PROJECT_NAME}_voice_node
    ${catkin_LIBRARIES}
 )
 
+target_link_libraries(${PROJECT_NAME}_motion_control_node
+   ${catkin_LIBRARIES}
+)
+
 #############
 ## Install ##
 #############

+ 35 - 0
src/robot_demo/include/motion_control_demo.h

@@ -0,0 +1,35 @@
+/*
+ * @Copyright(C): 2016-2021 ROS小课堂 www.corvin.cn
+ * @Author: adam_zhuo
+ * @Date: 2021-05-13 10:41:10
+ * @Description: 运动控制头文件
+ * @History: 20210429:初始化文件-adam_zhuo
+ */
+
+#ifndef _MOTION_CONTROL_DEMO_H
+#define _MOTION_CONTROL_DEMO_H
+
+#include <ros/ros.h>
+#include <std_msgs/String.h>
+#include <geometry_msgs/Twist.h>
+#include "ros_arduino_msgs/GripperAngle.h"
+#include "ros_arduino_msgs/GripperControl.h"
+
+class Motion_Control_Demo
+{
+private:
+    ros::NodeHandle _nh;
+    ros::Publisher _cmd_vel_pub;
+    geometry_msgs::Twist _twist;
+    ros::ServiceClient _gripper_srv_client;
+    ros::ServiceClient _control_srv_client;
+    ros_arduino_msgs::GripperAngle _gripper_srv;
+    ros_arduino_msgs::GripperControl _control_srv;
+    
+public:
+    Motion_Control_Demo();
+    ~Motion_Control_Demo();
+    void motion_control();
+};
+
+#endif

+ 14 - 0
src/robot_demo/launch/motion_control_demo.launch

@@ -0,0 +1,14 @@
+<!--
+ * @Copyright(C): 2016-2021 ROS小课堂 www.corvin.cn
+ * @Author: adam_zhuo
+ * @Date: 2021-05-13 09:53:40
+ * @Description: 启动运动控制demo节点
+ * @History: 20210513:初始化文件-adam_zhuo
+-->
+
+<launch>
+  <!-- 启动robot_demo_motion_control_node -->
+  <node pkg="robot_demo" type="robot_demo_motion_control_node" name="robot_demo_motion_control_node" output="screen">
+
+  </node>
+</launch>

+ 0 - 0
src/robot_demo/src/infrared_demo.cpp → src/robot_demo/src/infrared_demo_node.cpp


+ 62 - 0
src/robot_demo/src/motion_control_demo_node.cpp

@@ -0,0 +1,62 @@
+/*
+ * @Copyright(C): 2016-2021 ROS小课堂 www.corvin.cn
+ * @Author: adam_zhuo
+ * @Date: 2021-05-13 10:48:33
+ * @Description: 运动控制demo
+ * @History: 20210429:初始化文件-adam_zhuo
+ */
+
+#include "motion_control_demo.h"
+
+Motion_Control_Demo::Motion_Control_Demo(){
+
+    //注册发布者和服务
+    _cmd_vel_pub = _nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
+    _gripper_srv_client = _nh.serviceClient<ros_arduino_msgs::GripperAngle>("/mobilebase_arduino/gripper_angle");
+    _control_srv_client = _nh.serviceClient<ros_arduino_msgs::GripperControl>("/mobilebase_arduino/gripper_control");
+    //旋转角速度为0.3
+    _twist.angular.z = 0.3;
+    Motion_Control_Demo::motion_control();
+}
+
+Motion_Control_Demo::~Motion_Control_Demo(){
+
+}
+
+void Motion_Control_Demo::motion_control(){
+
+    //控制小车原地转弯
+    for (int i = 0; i < 10; i++){
+        _cmd_vel_pub.publish(_twist);
+        ros::Duration(0.10).sleep();
+    }
+    _twist.angular.z = 0;
+    _cmd_vel_pub.publish(_twist);
+
+    //控制夹爪张开到35,范围为0-65
+    _gripper_srv.request.servoID = 1;
+    _gripper_srv.request.angle = 35;
+    _gripper_srv.request.delay = 0;
+    _gripper_srv_client.call(_gripper_srv);
+
+    //控制夹爪上升
+    _control_srv.request.servoID = 0;
+    //1为夹爪上升
+    _control_srv.request.value = 1;
+    _control_srv_client.call(_control_srv);
+    //上升1s
+    ros::Duration(1).sleep();
+    //2为上升停止
+    _control_srv.request.value = 2;
+    _control_srv_client.call(_control_srv);
+}
+
+int main(int argc, char **argv){
+
+    //初始化节点
+    ros::init(argc, argv, "motion_control_demo_node");
+    //根据Motion_Control_Demo声明对象,调用构造函数
+    Motion_Control_Demo motion_control_demo;
+    //使ROS中回调函数生效
+    ros::spin();
+}

+ 6 - 2
src/robot_demo/src/voice_demo_node.cpp

@@ -2,16 +2,20 @@
  * @Copyright(C): 2016-2021 ROS小课堂 www.corvin.cn
  * @Author: adam_zhuo
  * @Date: 2021-05-13 10:09:03
- * @Description: file content
+ * @Description: 语音demo
  * @History: 20210429:-adam_zhuo
  */
 
 #include "voice_demo.h"
 
 Voice_Demo::Voice_Demo(){
+
+    //注册语音发布者
     _voice_pub = nh.advertise<std_msgs::String>("/voice_system/iflytek_offline_tts_topic", 1);
+    //要发布的内容
     std_msgs::String data;
-    data->data = "你好";
+    data.data = "你好";
+    //每隔2s发布一次
     ros::Rate rate(0.5);
     while (true){
         _voice_pub.publish(data);