libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
generate_joint_velocity_motion_external_control_loop.cpp

An example showing how to generate a joint velocity motion with an external control loop.

An example showing how to generate a joint velocity motion with an external control loop.

Warning
Before executing this example, make sure there is enough space in front of the robot.
// Copyright (c) 2023 Franka Robotics GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#include <cmath>
#include <iostream>
#include <franka/robot.h>
int main(int argc, char** argv) {
// Check whether the required arguments were passed
if (argc != 2) {
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
return -1;
}
try {
franka::Robot robot(argv[1]);
setDefaultBehavior(robot);
// First move the robot to a suitable joint configuration
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
MotionGenerator motion_generator(0.5, q_goal);
std::cout << "WARNING: This example will move the robot! "
<< "Please make sure to have the user stop button at hand!" << std::endl
<< "Press Enter to continue..." << std::endl;
std::cin.ignore();
robot.control(motion_generator);
std::cout << "Finished moving to initial joint configuration." << std::endl;
// Set additional parameters always before the control loop, NEVER in the control loop!
// Set collision behavior.
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
{{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}}, {{20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0}},
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}},
{{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}}, {{20.0, 20.0, 20.0, 25.0, 25.0, 25.0}});
double time_max = 1.0;
double omega_max = 1.0;
double time = 0.0;
auto callback_control = [=, &time](const franka::RobotState&,
time += period.toSec();
double cycle = std::floor(std::pow(-1.0, (time - std::fmod(time, time_max)) / time_max));
double omega = cycle * omega_max / 2.0 * (1.0 - std::cos(2.0 * M_PI / time_max * time));
franka::JointVelocities velocities = {{0.0, 0.0, 0.0, omega, omega, omega, omega}};
if (time >= 2 * time_max) {
std::cout << std::endl << "Finished motion, shutting down example" << std::endl;
return franka::MotionFinished(velocities);
}
return velocities;
};
bool motion_finished = false;
auto active_control = robot.startJointVelocityControl(
research_interface::robot::Move::ControllerMode::kJointImpedance);
while (!motion_finished) {
auto read_once_return = active_control->readOnce();
auto robot_state = read_once_return.first;
auto duration = read_once_return.second;
auto joint_velocities = callback_control(robot_state, duration);
motion_finished = joint_velocities.motion_finished;
active_control->writeOnce(joint_velocities);
}
} catch (const franka::Exception& e) {
std::cout << e.what() << std::endl;
return -1;
}
return 0;
}
Implements the ActiveControlBase abstract class.
Contains the franka::ActiveMotionGenerator type.
An example showing how to generate a joint pose motion to a goal position.
Definition examples_common.h:31
Represents a duration with millisecond resolution.
Definition duration.h:19
Stores values for joint velocity motion generation.
Definition control_types.h:99
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition robot.h:68
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
void setCollisionBehavior(const std::array< double, 7 > &lower_torque_thresholds_acceleration, const std::array< double, 7 > &upper_torque_thresholds_acceleration, const std::array< double, 7 > &lower_torque_thresholds_nominal, const std::array< double, 7 > &upper_torque_thresholds_nominal, const std::array< double, 6 > &lower_force_thresholds_acceleration, const std::array< double, 6 > &upper_force_thresholds_acceleration, const std::array< double, 6 > &lower_force_thresholds_nominal, const std::array< double, 6 > &upper_force_thresholds_nominal)
Changes the collision behavior.
virtual std::unique_ptr< ActiveControlBase > startJointVelocityControl(const research_interface::robot::Move::ControllerMode &control_type)
Starts a new joint velocity motion generator.
Contains common types and functions for the examples.
Contains exception definitions.
Contains the franka::Robot type.
Base class for all exceptions used by libfranka.
Definition exception.h:20
Describes the robot state.
Definition robot_state.h:34