Skip to content

Commit

Permalink
Merge pull request #41 in SRR/franka_ros2 from hotfix/do-not-activate…
Browse files Browse the repository at this point in the history
…-torque-unless-commanded to humble

* commit '981a23c68efb7644bf868f58f2bd035e9b6bdd86':
  fix: start torque controller in perform_command_mode_switch
  • Loading branch information
BarisYazici committed Aug 24, 2023
2 parents 5273252 + 981a23c commit d52354c
Show file tree
Hide file tree
Showing 15 changed files with 99 additions and 26 deletions.
6 changes: 6 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,11 @@
# Changelog

## 0.1.3 - 2023-08-24

Requires libfranka >= 0.11.0, required ROS 2 Humble

* franka\_hardware: hotfix start controller when user claims the command interface

## 0.1.2 - 2023-08-21

Requires libfranka >= 0.11.0, required ROS 2 Humble
Expand Down
2 changes: 1 addition & 1 deletion franka_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>franka_bringup</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>Package with launch files and run-time configurations for using Franka Emika research robots with ros2_control</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion franka_description/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>franka_description</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>franka_description contains URDF files and meshes of Franka Emika robots</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion franka_example_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>franka_example_controllers</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>franka_example_controllers provides example code for controlling Franka Emika research robots with ros2_control</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion franka_gripper/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>franka_gripper</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>This package implements the franka gripper of type Franka Hand for the use in ROS2</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,8 @@ class FrankaHardwareInterface : public hardware_interface::SystemInterface {
Model* hw_franka_model_ptr_ = nullptr;

bool effort_interface_claimed_ = false;
bool effort_interface_running_ = false;

static rclcpp::Logger getLogger();

const std::string k_robot_name{"panda"};
Expand Down
13 changes: 11 additions & 2 deletions franka_hardware/include/franka_hardware/robot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,11 @@ class Robot {
/// Starts a read / write communication with the connected robot
virtual void initializeReadWriteInterface();

/// stops the read / write communication with the connected robot
/// stops the read continous communication with the connected robot
virtual void stopRobot();

/**
* Get the current robot state in a thread-safe way.
* Get the current robot state
* @return current robot state.
*/
virtual franka::RobotState readOnce();
Expand Down Expand Up @@ -192,13 +192,22 @@ class Robot {
Robot() = default;

private:
/**
* Get the current robot state, when the controller is active
* @return current robot state.
*/
virtual franka::RobotState readOnceActiveControl();

std::mutex write_mutex_;
std::mutex control_mutex_;

std::unique_ptr<franka::Robot> robot_;
std::unique_ptr<franka::ActiveControl> active_control_;
std::unique_ptr<franka::Model> model_;
std::unique_ptr<Model> franka_hardware_model_;

std::array<double, 7> last_desired_torque_ = {0, 0, 0, 0, 0, 0, 0};
bool control_loop_active_{false};
franka::RobotState current_state_;
};
} // namespace franka_hardware
2 changes: 1 addition & 1 deletion franka_hardware/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>franka_hardware</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>franka_hardware provides hardware interfaces for using Franka Emika research robots with ros2_control</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down
18 changes: 15 additions & 3 deletions franka_hardware/src/franka_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@ std::vector<CommandInterface> FrankaHardwareInterface::export_command_interfaces

CallbackReturn FrankaHardwareInterface::on_activate(
const rclcpp_lifecycle::State& /*previous_state*/) {
robot_->initializeReadWriteInterface();
hw_commands_.fill(0);
read(rclcpp::Time(0),
rclcpp::Duration(0, 0)); // makes sure that the robot state is properly initialized.
Expand Down Expand Up @@ -105,8 +104,13 @@ hardware_interface::return_type FrankaHardwareInterface::write(const rclcpp::Tim
[](double hw_command) { return !std::isfinite(hw_command); })) {
return hardware_interface::return_type::ERROR;
}

robot_->writeOnce(hw_commands_);
if (effort_interface_running_) {
robot_->writeOnce(hw_commands_);
} else {
RCLCPP_FATAL(getLogger(),
"Effort interface is not running. Did you claim the command interface?");
return hardware_interface::return_type::ERROR;
}
return hardware_interface::return_type::OK;
}

Expand Down Expand Up @@ -185,6 +189,14 @@ rclcpp::Logger FrankaHardwareInterface::getLogger() {
hardware_interface::return_type FrankaHardwareInterface::perform_command_mode_switch(
const std::vector<std::string>& /*start_interfaces*/,
const std::vector<std::string>& /*stop_interfaces*/) {
if (!effort_interface_running_ && effort_interface_claimed_) {
robot_->stopRobot();
robot_->initializeReadWriteInterface();
effort_interface_running_ = true;
} else if (effort_interface_running_ && !effort_interface_claimed_) {
robot_->stopRobot();
effort_interface_running_ = false;
}
return hardware_interface::return_type::OK;
}

Expand Down
34 changes: 25 additions & 9 deletions franka_hardware/src/robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,29 @@ Robot::Robot(const std::string& robot_ip, const rclcpp::Logger& logger) {
franka_hardware_model_ = std::make_unique<Model>(model_.get());
}

Robot::~Robot() {
stopRobot();
}

franka::RobotState Robot::readOnce() {
std::lock_guard<std::mutex> lock(control_mutex_);
if (!control_loop_active_) {
return robot_->readOnce();
} else {
return readOnceActiveControl();
}
}

void Robot::stopRobot() {
if (control_loop_active_) {
control_loop_active_ = false;
active_control_.reset();
}
}

void Robot::writeOnce(const std::array<double, 7>& efforts) {
std::lock_guard<std::mutex> lock(control_mutex_);

auto torque_command = franka::Torques(efforts);
torque_command.tau_J =
franka::limitRate(franka::kMaxTorqueRate, torque_command.tau_J, last_desired_torque_);
Expand All @@ -48,7 +70,8 @@ void Robot::writeOnce(const std::array<double, 7>& efforts) {
active_control_->writeOnce(torque_command);
}

franka::RobotState Robot::readOnce() {
franka::RobotState Robot::readOnceActiveControl() {
// When controller is active use active control to read the robot state
const auto [robot_state, _] = active_control_->readOnce();
return robot_state;
}
Expand All @@ -57,11 +80,8 @@ franka_hardware::Model* Robot::getModel() {
return franka_hardware_model_.get();
}

void Robot::stopRobot() {
active_control_.reset();
}

void Robot::initializeReadWriteInterface() {
control_loop_active_ = true;
active_control_ = robot_->startTorqueControl();
}

Expand Down Expand Up @@ -168,8 +188,4 @@ void Robot::setFullCollisionBehavior(
lower_force_thresholds_nominal, upper_force_thresholds_nominal);
}

Robot::~Robot() {
stopRobot();
}

} // namespace franka_hardware
34 changes: 31 additions & 3 deletions franka_hardware/test/franka_hardware_interface_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,7 @@ TEST(

EXPECT_CALL(*mock_robot, getModel()).WillOnce(testing::Return(model_address));
EXPECT_CALL(*mock_robot, readOnce()).WillOnce(testing::Return(robot_state));

franka_hardware::FrankaHardwareInterface franka_hardware_interface(std::move(mock_robot));

const auto hardware_info = createHardwareInfo();
Expand Down Expand Up @@ -226,8 +227,8 @@ TEST(

MockModel mock_model;
MockModel* model_address = &mock_model;

EXPECT_CALL(*mock_robot, readOnce()).WillOnce(testing::Return(robot_state));

EXPECT_CALL(*mock_robot, getModel()).WillOnce(testing::Return(model_address));
franka_hardware::FrankaHardwareInterface franka_hardware_interface(mock_robot);

Expand Down Expand Up @@ -258,7 +259,6 @@ TEST(

MockModel mock_model;
MockModel* model_address = &mock_model;

EXPECT_CALL(*mock_robot, readOnce()).WillOnce(testing::Return(robot_state));
EXPECT_CALL(*mock_robot, getModel()).WillOnce(testing::Return(model_address));
franka_hardware::FrankaHardwareInterface franka_hardware_interface(mock_robot);
Expand Down Expand Up @@ -366,6 +366,20 @@ TEST(FrankaHardwareIntefaceTest, when_write_called_expect_ok) {

const auto hardware_info = createHardwareInfo();
franka_hardware_interface.on_init(hardware_info);
std::vector<std::string> start_interface;

for (size_t i = 0; i < hardware_info.joints.size(); i++) {
const std::string joint_name = k_joint_name + std::to_string(i);
start_interface.push_back(joint_name + "/" + k_effort_controller);
}

std::vector<std::string> stop_interface = {};

EXPECT_EQ(franka_hardware_interface.prepare_command_mode_switch(start_interface, stop_interface),
hardware_interface::return_type::OK);
// can call write only after switching to the torque controller
EXPECT_EQ(franka_hardware_interface.perform_command_mode_switch(start_interface, stop_interface),
hardware_interface::return_type::OK);

const auto time = rclcpp::Time(0, 0);
const auto duration = rclcpp::Duration(0, 0);
Expand All @@ -382,7 +396,6 @@ TEST(FrankaHardwareInterfaceTest, when_on_activate_called_expect_success) {
auto mock_robot = std::make_shared<MockRobot>();
EXPECT_CALL(*mock_robot, readOnce()).WillOnce(testing::Return(robot_state));
EXPECT_CALL(*mock_robot, getModel()).WillOnce(testing::Return(model_address));
EXPECT_CALL(*mock_robot, initializeReadWriteInterface());

franka_hardware::FrankaHardwareInterface franka_hardware_interface(mock_robot);

Expand Down Expand Up @@ -426,6 +439,21 @@ TEST(FrankaHardwareInterfaceTest,
hardware_interface::return_type::OK);
}

TEST(FrankaHardwareInterfaceTest,
given_effort_interface_not_claimed_when_write_called_expect_error_response) {
auto mock_robot = std::make_shared<MockRobot>();

franka_hardware::FrankaHardwareInterface franka_hardware_interface(mock_robot);

const auto time = rclcpp::Time(0, 0);
const auto duration = rclcpp::Duration(0, 0);

const auto hardware_info = createHardwareInfo();
franka_hardware_interface.on_init(hardware_info);
EXPECT_EQ(franka_hardware_interface.write(time, duration),
hardware_interface::return_type::ERROR);
}

TEST(FrankaHardwareInterfaceTest,
given_that_effort_control_started_perform_command_mode_switch_stop_expect_ok) {
auto mock_robot = std::make_shared<MockRobot>();
Expand Down
2 changes: 1 addition & 1 deletion franka_moveit_config/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>franka_moveit_config</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>Contains Moveit2 configuration files for Franka Emika research robots</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion franka_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>franka_msgs</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>franka_msgs provides messages and actions specific to Franka Emika research robots</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion franka_robot_state_broadcaster/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>franka_robot_state_broadcaster</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>Broadcaster to publish robot states</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion integration_launch_testing/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>integration_launch_testing</name>
<version>0.1.2</version>
<version>0.1.3</version>
<description>Functional integration tests for franka controllers</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
Expand Down

0 comments on commit d52354c

Please sign in to comment.