Robotics StackExchange | Archived questions

hardware robot moment issue, not following gazebo simulation trajectory

we made robot hardware running with nema 17 stepper motors without encoders of DM542 stepper drivers and arduino ...when we execute the commands, all working well in gazebo simulation world, but same trajectories are not following with the real time hardware robot, the robotic arm is moving ahead of its designated point and then coming back to the same point. so finally end effector is reaching goal position but following strange trajectories..as on search we couldnt find the arduino stepper motor code for drivers, we written code as ourselves, i think problem is all about arduino code , we tried a lot with code ..but could not make it i am attaching youtube video link that shows real hardware and gazebo simulation...and also attaching the arduino code as well...kindly suggest some solution to the problem........thank you

Ros source package link : robot_source youtube link: https://youtu.be/R2brv3ZZEIk arduino code:

#include <ros.h>

#include <std_msgs/Empty.h>

#include <std_msgs/String.h>

#include <std_msgs/Int8.h>

#include <std_msgs/Int16.h>

#include <std_msgs/UInt16MultiArray.h>

#include <mwc_stepper.h>

#include <math.h>

#include <AccelStepper.h>

//#include <MultiStepper.h>


#define PUL1 5

#define DIR1 4


#define PUL2 7

#define DIR2 6


#define PUL3 9

#define DIR3 8


// Define the working range for each joint

#define MIN_RANGE 0

#define MAX_RANGE 180


int posfactor = 19/(0.225*2);

int posfactor_1 = 14/(0.225*2);

int directionMultiplier = 1;


// Defining ROS node handle.

ros::NodeHandle nh;


AccelStepper base(AccelStepper::DRIVER, PUL1, DIR1);

AccelStepper shoulder(AccelStepper::DRIVER, PUL2, DIR2);

AccelStepper elbow(AccelStepper::DRIVER, PUL3, DIR3);


//MultiStepper robojoints;


void reach_goal(AccelStepper& motor, int goal){

  if(goal>=motor.currentPosition()){

    // goes from the start point degrees to the end point degrees

    directionMultiplier = 1;

    motor.moveTo(directionMultiplier * goal);

  } else{

    // goes from the end point degrees to the start point degrees

    directionMultiplier = -1;

    motor.moveTo(directionMultiplier * goal);

  }

}


void arm_actuate_cb( const std_msgs::UInt16MultiArray& msg){


  // check that the received data are bounded correctly

  if(msg.data[0]<MIN_RANGE) msg.data[0] = MIN_RANGE;

  if(msg.data[1]<MIN_RANGE) msg.data[1] = MIN_RANGE;

  if(msg.data[2]<MIN_RANGE) msg.data[2] = MIN_RANGE;

  //if(msg.data[3]<MIN_RANGE) msg.data[3] = MIN_RANGE;


  if(msg.data[0]>MAX_RANGE) msg.data[0] = MAX_RANGE;

  if(msg.data[1]>MAX_RANGE) msg.data[1] = MAX_RANGE;

  if(msg.data[2]>MAX_RANGE) msg.data[2] = MAX_RANGE;

  //if(msg.data[3]>MAX_RANGE) msg.data[3] = MAX_RANGE;


  reach_goal(base, msg.data[0] * posfactor);

  reach_goal(shoulder, msg.data[1] * posfactor);

  reach_goal(elbow, msg.data[2] * posfactor_1);

}


// Define the subscriber to the topic /servo_actuate where are published UInt16MultiArray messages

// Define the function that will be triggered each time a new message is published on this topic


ros::Subscriber<std_msgs::UInt16MultiArray> sub("arduino/arm_actuate", &arm_actuate_cb );


void setup() {

  // Attach and Initialize each Servo to the Arduino pin where it is connected

    base.setMaxSpeed(1000.0);

    base.setAcceleration(200.0);

    //base.moveTo(400);



    shoulder.setMaxSpeed(1000.0);

    shoulder.setAcceleration(200.0);

    //shoulder.moveTo(400);



    elbow.setMaxSpeed(1000.0);

    elbow.setAcceleration(200.0);

    //elbow.moveTo(400);


  // Inizialize the ROS node on the Arduino

  nh.initNode();

  // Inform ROS that this node will subscribe to messages on a given topic

  nh.subscribe(sub);

}


void loop() {

    //if (base.distanceToGo() == 0)

  //base.moveTo(-base.currentPosition());

    base.run();

    shoulder.run();

    elbow.run();

  // Keep the ROS node up and running

  nh.spinOnce();

  delay(1);

}

Asked by jagilamkumar on 2022-12-24 00:25:51 UTC

Comments

If it were me, I'd write test programs to verify you are able to move each joint through its full 0-180° motion. The video makes it look like there is some mismatch with the command sent to the 3nd joint (the elbow?) - perhaps the physical joint's 0° is not where you think it is.

Asked by Mike Scheutzow on 2022-12-24 10:33:40 UTC

thank you for the comment, but Physical joints's 0° can't be determined in my case as i am currently using open-loop system. my NEMA 17 stepper motor doesn't have encoder.

Asked by jagilamkumar on 2022-12-26 02:01:33 UTC

For robot arms, all the arm-movement code I'm aware of relies on having the current value of each joint. Open loop is seen as too imprecise. Do you have any plan in mind to obtain this joint information?

Asked by Mike Scheutzow on 2022-12-28 09:56:57 UTC

Answers