Implementing PID Position control - RoboClaw

Hi,

I urgently need help with my setup please!

I have a linear actuator with built in potentiometer feedback. I have connected this to a 2V supply and the wiper to pin EN1.

I want to control the length of the actuator using the PID controller on my RoboClaw 30A using the USB interface.

Here is my approach in software:
Start-up and connect over USB
Set encoder mode to 0x81
Set Velocity PID parameters (even though i am not controlling the velocity, but position - do i need this?!)
Set Position PID parameters
Reset encoders
Set the target position
After setting position sit in while loop and read feedback.

#include "roboclaw_driver/RoboClaw.h"
#include "roboclaw_driver/motor_state.h"
#include "roboclaw_driver/claw_state.h"
#include <ros/ros.h>
#include <ros/console.h>
#include "std_msgs/String.h"

#define ADDRESS 0x80

using namespace std;

class Driver {

private:
  ros::NodeHandle nh_;
  ros::Publisher pub_;

  string port;
  USBSerial serial;
  RoboClaw claw_;

  struct claw_properties_t {
    string version;
    int year;
  } claw_properties;

  int address_;
  int serial_errs_;

public:

    explicit Driver(const ros::NodeHandle &node)
  {

      pub_ = nh_.advertise<roboclaw_driver::claw_state>("claw_state", 5);
    bool valid;
    }

    ~Driver() {
    }

void getState(void)
{
    roboclaw_driver::claw_state state_;
    uint8_t status;
    bool valid;

    int16_t m1_current, m2_current;
    uint8_t mode1=5, mode2=5;

    valid = claw_.ReadEncMode(ADDRESS, mode1, mode2);

    state_.m1_enc = claw_.ReadEncM1(ADDRESS, &status,&valid);
    state_.m2_enc = claw_.ReadEncM2(ADDRESS, &status,&valid);
    state_.v = claw_.ReadSpeedM1(ADDRESS, &status, &valid);
    state_.w = state_.m1_enc;
    uint32_t p,i,d,qpps;
    claw_.ReadPIDM1(ADDRESS, p, i, d, qpps );
    state_.left_pid_pe = p;
    state_.left_pid_ie = i;
    state_.left_pid_de = d;
    state_.left_qpps = qpps;
    claw_.ReadPIDM2(ADDRESS, p, i, d, qpps );
    state_.right_pid_pe = p;
    state_.right_pid_ie = i;
    state_.right_pid_de = d;
    state_.right_qpps = qpps;
    state_.main_voltage = claw_.ReadMainBatteryVoltage(ADDRESS,&valid);
    state_.logic_voltage = claw_.ReadLogicBattVoltage(ADDRESS,&valid);
    claw_.ReadCurrents(ADDRESS, m1_current, m2_current);
    state_.m1_current = m1_current;
    state_.m2_current = m2_current;

    pub_.publish(state_);
}

void basic() {
  ros::NodeHandle nh;
  uint8_t status;
  bool valid;

  port = "/dev/roboclaw";//TODO: Don't hardcode port

  serial.Open(port.c_str());
  claw_ = RoboClaw(&serial);

  //Use Absolute Encoder and Enable encoders in RC mode
  claw_.SetM1EncoderMode(ADDRESS,3);
  claw_.SetM2EncoderMode(ADDRESS,3);

  //Set PID Coefficients
  claw_.SetM1Constants(ADDRESS,0X00004000,0x00010000 ,0x00008000,3600);
  claw_.SetM2Constants(ADDRESS,0X00004000,0x00010000 ,0x00008000,3600);

  claw_.SetM1PstnConsts(ADDRESS,20000,2000,4,10000,10,0,21000);//D P I IMAX DEAD MIN MAX
  claw_.SetM2PstnConsts(ADDRESS,20000,2000,4,10000,10,0,21000);//D P I IMAX DEAD MIN MAX

  //Save settings in Roboclaw eeprom.  Uncomment to save settings.
  //roboclaw.WriteNVM(address);

  claw_.ResetEncoders(ADDRESS);

  uint32_t accel = 0, decel = accel, vel=1200, pstn=1300;
    claw_.SpeedAccelDeccelPositionM1(ADDRESS,accel,vel,decel,pstn,1);
    claw_.SpeedAccelDeccelPositionM2(ADDRESS,accel,vel,decel,pstn,1);

    claw_.SpeedAccelDistanceM1(ADDRESS, 0, 3600, 100, 1);
    claw_.SpeedAccelDistanceM2(ADDRESS, 0, 3600, 100, 1);

    while (ros::ok()) {
      ros::Duration(0.5).sleep();

      getState();

      ros::spinOnce();
    }
}
};//End class

int main(int argc, char **argv) {
  ros::init(argc, argv, "enc_demo");
  ros::NodeHandle n;

  Driver driver(n);
  driver.basic();
}

Hello.

My understanding is that the RoboClaw only works with incremental quadrature encoder feedback, though the user’s guide does not appear to be entirely clear on that, so you might try contacting the manufacturer, Orion Robotics, for a more definitive answer. We recommend our jrk motor controllers for applications like yours.

-Jon