Use joint potentiometers for position control with Dynamixel motors and ros_control

asked 2022-10-07 02:40:08 -0500

volvo2 gravatar image

Hi, We are building a dexterous robotic hand, with Dynamixel XC330 actuators and remote actuation. We have implemented joint potentiometers (bourns 10k 3382G), to account for possible slack in the tendons. We want to implement position control using the EffortJointInterface and the joint potentiometers instead of the motor encoders. Using the template from open_manipulators (https://github.com/ROBOTIS-GIT/open_m...) we have now implemented the hardware abstraction layer. However, here we are using the motor encoders and not the joint potentiometers. How do we go about implementing the joint potentiometers in the hardware abstraction layer?

  1. Do we declare the potentiometers state as a variable in the hardware_interface.h file, as we have done for the dynamixel variables?

roboys_hw_interface.h:

#ifndef ROBOYS_HARDWARE_INTERFACE_H
#define ROBOYS_HARDWARE_INTERFACE_H

#include <yaml-cpp/yaml.h>

#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <controller_manager/controller_manager.h>
#include <hardware_interface/joint_command_interface.h>
#include <hardware_interface/joint_state_interface.h>
#include <hardware_interface/robot_hw.h>

#include "dynamixel_workbench_toolbox/dynamixel_workbench.h"

typedef struct _ItemValue
{
  std::string item_name;
  int32_t value;
} ItemValue;

typedef struct _WayPoint
{
  double position;
  double velocity;
  double acceleration;
} WayPoint;

typedef struct _Joint
{
  double position;
  double velocity;
  double current;
  double effort;
  double position_command;
  double velocity_command;
  double effort_command;
} Joint;

namespace roboys_hw_interface
{
class HardwareInterface : public hardware_interface::RobotHW
{
 public:
  HardwareInterface(ros::NodeHandle nh, ros::NodeHandle private_nh);
  ~HardwareInterface() {}

  void read();
  void write();

 private:
  void registerActuatorInterfaces();
  void registerControlInterfaces();
  bool initWorkbench(const std::string port_name, const uint32_t baud_rate);
  bool getDynamixelsInfo(const std::string yaml_file);
  bool loadDynamixels(void);
  bool initDynamixels(void);
  bool initControlItems(void);
  bool initSDKHandlers(void);

  // ROS NodeHandle
  ros::NodeHandle node_handle_;
  ros::NodeHandle priv_node_handle_;

  // ROS Parameters
  std::string port_name_;
  int32_t baud_rate_;
  std::string yaml_file_;
  std::string interface_;

  // Variables
  DynamixelWorkbench *dxl_wb_;
  std::map<std::string, uint32_t> dynamixel_;
  std::map<std::string, const ControlItem*> control_items_;
  std::vector<std::pair<std::string, ItemValue>> dynamixel_info_;
  std::vector<Joint> joints_;

  // ROS Control interfaces
  hardware_interface::JointStateInterface joint_state_interface_;
  hardware_interface::PositionJointInterface position_joint_interface_;
  hardware_interface::VelocityJointInterface velocity_joint_interface_;
  hardware_interface::EffortJointInterface effort_joint_interface_;
};

} // namespace roboys_hw_interface
#endif // ROBOYS_HARDWARE_INTERFACE_H
  1. And is it then possible to adapt the .cpp file to declare the position from the joint potentiometer and not the motor encoder? Thank you in advance. Kind regards, Anders
edit retag flag offensive close merge delete