no message
parent
737b3ce532
commit
1ea005d398
|
@ -28,6 +28,7 @@
|
||||||
#include <AccelStepper.h>
|
#include <AccelStepper.h>
|
||||||
#include <MultiStepper.h>
|
#include <MultiStepper.h>
|
||||||
|
|
||||||
|
|
||||||
// Joint 1
|
// Joint 1
|
||||||
#define E1_STEP_PIN 53
|
#define E1_STEP_PIN 53
|
||||||
#define E1_DIR_PIN 51
|
#define E1_DIR_PIN 51
|
||||||
|
@ -58,6 +59,8 @@
|
||||||
#define E0_ENABLE_PIN 24
|
#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 joint1(1,E1_STEP_PIN, E1_DIR_PIN);
|
||||||
AccelStepper joint2(1,Z_STEP_PIN, Z_DIR_PIN);
|
AccelStepper joint2(1,Z_STEP_PIN, Z_DIR_PIN);
|
||||||
AccelStepper joint3(1,Y_STEP_PIN, Y_DIR_PIN);
|
AccelStepper joint3(1,Y_STEP_PIN, Y_DIR_PIN);
|
||||||
|
@ -74,7 +77,7 @@ ros::NodeHandle nh;
|
||||||
std_msgs::Int16 msg;
|
std_msgs::Int16 msg;
|
||||||
|
|
||||||
//instantiate publisher (for debugging purposes)
|
//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){
|
void arm_cb(const moveo_moveit::ArmJointState& arm_steps){
|
||||||
joint_status = 1;
|
joint_status = 1;
|
||||||
|
@ -138,8 +141,8 @@ void loop() {
|
||||||
positions[4] = -joint_step[4];
|
positions[4] = -joint_step[4];
|
||||||
|
|
||||||
// Publish back to ros to check if everything's correct
|
// Publish back to ros to check if everything's correct
|
||||||
//msg.data=positions[4];
|
msg.data=positions[4];
|
||||||
//steps.publish(&msg);
|
steps.publish(&msg);
|
||||||
|
|
||||||
steppers.moveTo(positions);
|
steppers.moveTo(positions);
|
||||||
nh.spinOnce();
|
nh.spinOnce();
|
||||||
|
|
Loading…
Reference in New Issue