From 1ea005d398bed2c5a837c3365657afd2fac35455 Mon Sep 17 00:00:00 2001 From: "LAPTOP-HS5NB06S\\29019" <290198252@qq.com> Date: Tue, 16 Jun 2020 11:12:47 +0800 Subject: [PATCH] no message --- arduino/arduino/moveo_moveit/move_moveit/move_moveit.ino | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/arduino/arduino/moveo_moveit/move_moveit/move_moveit.ino b/arduino/arduino/moveo_moveit/move_moveit/move_moveit.ino index 7519372..ae025b8 100644 --- a/arduino/arduino/moveo_moveit/move_moveit/move_moveit.ino +++ b/arduino/arduino/moveo_moveit/move_moveit/move_moveit.ino @@ -28,6 +28,7 @@ #include #include + // Joint 1 #define E1_STEP_PIN 53 #define E1_DIR_PIN 51 @@ -58,6 +59,8 @@ #define E0_ENABLE_PIN 24 +// EG X-Y position bed driven by 2 steppers +// Alas its not possible to build an array of these with different pins for each :-( AccelStepper joint1(1,E1_STEP_PIN, E1_DIR_PIN); AccelStepper joint2(1,Z_STEP_PIN, Z_DIR_PIN); AccelStepper joint3(1,Y_STEP_PIN, Y_DIR_PIN); @@ -74,7 +77,7 @@ ros::NodeHandle nh; std_msgs::Int16 msg; //instantiate publisher (for debugging purposes) -//ros::Publisher steps("joint_steps_feedback",&msg); +ros::Publisher steps("joint_steps_feedback",&msg); void arm_cb(const moveo_moveit::ArmJointState& arm_steps){ joint_status = 1; @@ -138,8 +141,8 @@ void loop() { positions[4] = -joint_step[4]; // Publish back to ros to check if everything's correct - //msg.data=positions[4]; - //steps.publish(&msg); + msg.data=positions[4]; + steps.publish(&msg); steppers.moveTo(positions); nh.spinOnce();