frankaemika/franka_ros

Are ther available implementations using franka_hw::FrankaHW and franka::Robot usable for the following scenarios

Closed this issue · 3 comments

I have a code for controlling Franka Emika robot that uses the franka_hw::FrankaHW::control method. This method takes a lambda function and calls ros_control controller manager update internally and has resulted in some limitations.

Namely, while this control method is running, I can't call franka::Robot::readOnce() to read the state of the robot and send it to another node for example.

Secondly, if for some reason I want to manipulate the feedback to the controller, or the output from the controller, I can't do so (assuming I can't access the controller's implementation and can only access the ros_control hardware interface.

If I have understood correctly the above method internally uses franka::Robot::control method.

Do you know of any implementation that explicitely uses franka::Robot::control method to make the controll loop ?

Can you think of workarounds for the above scenarios if one had to still use franka_hw::FrankaHW::control method ?

Hello @a-z-e-r-i-l-a and sorry for the late reply,

This method takes a lambda function and calls ros_control controller manager update internally

I'm not quite sure what you mean here. AFAICS the FrankaHW::control() method does not call any update of a controller manager:

void FrankaHW::control(
const std::function<bool(const ros::Time&, const ros::Duration&)>& ros_callback) {
if (!initialized_) {
ROS_ERROR("FrankaHW: Call to control before initialization!");
return;
}
if (!controller_active_) {
return;
}
franka::Duration last_time = robot_state_ros_.time;
std::lock_guard<std::mutex> lock(robot_mutex_);
run_function_(*robot_, [this, ros_callback, &last_time](const franka::RobotState& robot_state,
franka::Duration time_step) {
if (last_time != robot_state.time) {
last_time = robot_state.time;
return ros_callback(ros::Time::now(), ros::Duration(time_step.toSec()));
}
return true;
});
}

Rather the controller manager is updated in the main loop in franka_control:

control_manager.update(now, now - last_time);


Namely, while this control method is running, I can't call franka::Robot::readOnce() to read the state of the robot and send it to another node for example.

This is expected behaviour since with ROS control the franka_control_node is calling Robot::control() (of libfranka) which does the spinning for you. As mentioned in the docs of Robot::readOnce():

Cannot be executed while a control or motion generator loop is running.


Secondly, if for some reason I want to manipulate the feedback to the controller, or the output from the controller, I can't do so (assuming I can't access the controller's implementation and can only access the ros_control hardware interface.

This is more tricky. AFAIK this is not easily possible in ROS control right now. There is this discussion where some people claim to have implemented "nested controller managers". Can this be an option for you? Create a custom ROS-control controller as a wrapper around your controller which adjusts the states & commands to your liking.


Do you know of any implementation that explicitely uses franka::Robot::control method to make the controll loop ?

Not to my knowledge sorry

Generally I'd say the approach would be to not fight but rather make use of the ROS control framework. Reading the state of the robot and sending commands to it, is can be done by writing your own ROS controller and claiming some robot interfaces.

Maybe a bit of context what you are trying to achieve here would also help to answer your question

I'll close this now because of inactivity, but feel free to reopen, should your problem persist