ros_controllers icon indicating copy to clipboard operation
ros_controllers copied to clipboard

Joint trajectory controller interface

Open Igorec opened this issue 11 years ago • 4 comments

Hi all! I have hardware that controls by position and velocity together in one command. So i use my own JointHandle analog:

class MyJointHandle : public hardware_interface::JointStateHandle
{
public:
  // ...
  void setCommand(double position, double velocity)
  {
    //...
  }
private:
  double* pos_cmd_;
  double* vel_cmd_;
};

I try to use joint_trajectory_controller::JointTrajectoryController, but it can work only with hardware_interface::JointHandle. But I think it can be improved by a little modification in files:

hardware_interface/internal/hardware_resource_manager.h

@@ -79,6 +79,9 @@
 class HardwareResourceManager : public HardwareInterface, public ResourceManager<ResourceHandle>
 {
 public:
+
+  typedef ResourceHandle ResourceHandleType;
+
   /** \name Non Real-Time Safe Functions
    *\{*/

joint_trajectory_controller/joint_trajectory_controller.h

@@ -171,10 +171,11 @@
   typedef typename Segment::Scalar Scalar;

   typedef HardwareInterfaceAdapter<HardwareInterface, typename Segment::State> HwIfaceAdapter;
+  typedef typename HardwareInterface::ResourceHandleType JointHandle;

   bool                                         verbose_;            ///< Hard coded verbose flag to help in debugging
   std::string                                  name_;               ///< Controller name.
-  std::vector<hardware_interface::JointHandle> joints_;             ///< Handles to controlled joints.
+  std::vector<JointHandle>                     joints_;     ///< Handles to controlled joints.

joint_trajectory_controller/hardware_interface_adapter.h

@@ -55,7 +55,7 @@
 class HardwareInterfaceAdapter
 {
 public:
-  bool init(std::vector<hardware_interface::JointHandle>& joint_handles, ros::NodeHandle& controller_nh)
+  bool init(std::vector<typename HardwareInterface::ResourceHandleType>& joint_handles, ros::NodeHandle& controller_nh)
   {
     return false;
   }

Could you improve that. Thanks.

Igorec avatar Mar 06 '14 13:03 Igorec

Good catch. Could you please submit the proposed changes as two pull requests, one for ros_control and one forros_controllers?.

Also, if you're interested in having the position+velocity command interface merged upstream, I would welcome a pull request against ros_control for the interface (preferably with tests), and another one against ros_controllers implementing the HardwareInterfaceAdaptor specialization for your type. I anticipate that you're not the only one interested in such an interface.

Thanks for your contribution.

adolfo-rt avatar Mar 06 '14 13:03 adolfo-rt

Ok. Thank you!

Igorec avatar Mar 06 '14 18:03 Igorec

I just posted 254 but is it possible this feature is what I am requesting?

anderwm avatar Mar 03 '17 16:03 anderwm

(you have linked the wrong issue in the url)

mathias-luedtke avatar Mar 04 '17 11:03 mathias-luedtke