|
@@ -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();
|
|
|
+}
|