10 #include <franka/exception.h>
11 #include <franka/robot.h>
14 #include <franka_msgs/ErrorRecoveryAction.h>
16 #include <std_srvs/Trigger.h>
19 using namespace std::chrono_literals;
21 int main(
int argc,
char** argv) {
22 ros::init(argc, argv,
"franka_control_node");
29 ROS_ERROR(
"franka_control_node: Failed to initialize FrankaHW class. Shutting down!");
33 auto services = std::make_unique<ServiceContainer>();
34 std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>
35 recovery_action_server;
37 std::atomic_bool has_error(
false);
39 auto connect = [&]() {
44 services = std::make_unique<ServiceContainer>();
47 recovery_action_server =
48 std::make_unique<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>(
49 node_handle,
"error_recovery",
50 [&](
const franka_msgs::ErrorRecoveryGoalConstPtr&) {
53 robot.automaticErrorRecovery();
55 recovery_action_server->setSucceeded();
57 }
catch (
const franka::Exception& ex) {
58 recovery_action_server->setAborted(franka_msgs::ErrorRecoveryResult(), ex.what());
63 recovery_action_server->start();
69 auto disconnect_handler = [&](std_srvs::Trigger::Request& request,
70 std_srvs::Trigger::Response&
response) ->
bool {
73 response.message =
"Controller is active. Cannot disconnect while a controller is running.";
77 recovery_action_server.reset();
80 response.message = result ?
"" :
"Failed to disconnect robot.";
84 auto connect_handler = [&](std_srvs::Trigger::Request& request,
85 std_srvs::Trigger::Response&
response) ->
bool {
88 response.message =
"Already connected to robot. Cannot connect twice.";
102 node_handle.
advertiseService<std_srvs::Trigger::Request, std_srvs::Trigger::Response>(
103 "connect", connect_handler);
105 node_handle.
advertiseService<std_srvs::Trigger::Request, std_srvs::Trigger::Response>(
106 "disconnect", disconnect_handler);
124 control_manager.update(now, now - last_time);
127 }
catch (
const std::logic_error& e) {
130 std::this_thread::sleep_for(1ms);
142 if (period.
toSec() == 0.0) {
144 control_manager.update(now, period, true);
145 franka_control.checkJointLimits();
146 franka_control.reset();
148 control_manager.update(now, period);
149 franka_control.checkJointLimits();
150 franka_control.enforceLimits(period);
154 }
catch (
const franka::ControlException& e) {