Robot joint state topic not showing after creating custom controller
Hello, I have created my custom PID controller for the rrbot 2DOF and I'm having a little issue. I'm controlling the first joint with my custom controller (effortcontroller with position inputs) and the second with an effortcontrollers/JointPositionController.
So far, the controller is loading well into gazebo, the parameter server shows all the parameters and when I publish a command for the first joint it works actually. My problem is that, when I do a rostopic list, there are differences between this two joints.
joint 1 shows:
/rrbot/joint1positioncontroller/command
and joint 2 shows:
/rrbot/joint2positioncontroller/command
/rrbot/joint2positioncontroller/pid/parameterdescriptions /rrbot/joint2positioncontroller/pid/parameterupdates
/rrbot/joint2positioncontroller/state
To progress with my work, I need to get acces to the /state topic of the joint 1 but i dont know what I'm missing. Here is my controller code:
#include <controller_interface/controller.h>
#include <hardware_interface/joint_command_interface.h>
#include <pluginlib/class_list_macros.h>
#include <std_msgs/Float64.h>
/*
Here, you are just including some files from other packages that are needed in order to create the controller,
and declaring a namespace for this class (namespaces provide a method to prevent name conflicts in large projects).
*/
namespace controller_ns {
/*
Here you are just declaring the class, which will be inherited from hardware_interface::EffortJointInterface.
This means that this controller will be able to control only joints that use an effort interface.
*/
class MyPositionController : public controller_interface::Controller<hardware_interface::EffortJointInterface> {
public:
/*
Here, you are creating the init() function, which will be called when your controller is loaded by the controller manager.
Inside this function, you will get the name of the joint that you will control from the Parameter Server first (so from the YAML file, which you will modify later), and then you will get the joint object to use in the realtime loop.
*/
bool init(hardware_interface::EffortJointInterface *hw, ros::NodeHandle &n) {
std::string my_joint;
if (!n.getParam("joint", my_joint)) {
ROS_ERROR("Could not find joint name");
return false;
}
joint_ = hw->getHandle(my_joint); // throws on failure
command_ = joint_.getPosition(); // set the current joint goal to the current joint position
// Load gain using gains set on parameter server
if (!n.getParam("kp", kp_))
{
ROS_ERROR("Could not find the gain parameter value");
return false;
}
// Load gain using gains set on parameter server
if (!n.getParam("ki", ki_))
{
ROS_ERROR("Could not find the gain parameter value");
return false;
}
// Load gain using gains set on parameter server
if (!n.getParam("kd", kd_))
{
ROS_ERROR("Could not find the gain parameter value");
return false;
}
// Start command subscriber
sub_command_ = n.subscribe<std_msgs::Float64>("command", 1, &MyPositionController::setCommandCB, this);
return true;
}
/*
Here you are defining the command that you are going to send to your joint.
In this case, it's a product between an error variable and a gain_ variable.
The error variable is defined as the difference between the current position
(joint_.getPosition()) of the joint and the goal position (setpoint_) of the joint.
PID o EL CONTROL
*/
void update(const ros::Time &time, const ros::Duration &period) {
double error = command_ - joint_.getPosition();
double dt = 0.01;
// P term
double P = (error * kp_);
// I term
double integral = integral + (error * dt);
double I = ki_ * integral;
//D term
double derivative = error / dt;
double D = kd_ * derivative;
double Out = P + I + D;
joint_.setCommand(Out);
}
void setCommandCB(const std_msgs::Float64ConstPtr& msg)
{
command_ = msg->data;
}
/*
Here, you are starting and stopping the controller.
Note that:
float and double are not of integral or enumeration type so they ahve to be declared as constexpr, or non-static.
*/
void starting(const ros::Time &time) {}
void stopping(const ros::Time &time) {}
private:
hardware_interface::JointHandle joint_;
double kp_;
double ki_;
double kd_;
double command_;
ros::Subscriber sub_command_;
};
/*
Here, you are calling the special macro plugin PLUGINLIB_EXPORT_CLASS
in order to allow this class to be dynamically loaded.
*/
PLUGINLIB_EXPORT_CLASS(controller_ns::MyPositionController,
controller_interface::ControllerBase);
} // namespace controller_ns
It would be helpful to have access to the code of the joint 2 controller to have a look and see what I'm missing.
Asked by mikell on 2023-01-16 05:21:14 UTC
Comments