An example showing how to use a joint velocity motion generator and torque control with an external control loop.
An example showing how to use a joint velocity motion generator and torque control with an external control loop.Additionally, this example shows how to capture and write logs in case an exception is thrown during a motion.
#include <cmath>
#include <fstream>
#include <iomanip>
#include <iostream>
#include <vector>
#include <Poco/DateTimeFormatter.h>
#include <Poco/File.h>
#include <Poco/Path.h>
namespace {
class Controller {
public:
Controller(size_t dq_filter_size,
const std::array<double, 7>& K_P,
const std::array<double, 7>& K_D)
: dq_current_filter_position_(0), dq_filter_size_(dq_filter_size), K_P_(K_P), K_D_(K_D) {
std::fill(dq_d_.begin(), dq_d_.end(), 0);
dq_buffer_ = std::make_unique<double[]>(dq_filter_size_ * 7);
std::fill(&dq_buffer_.get()[0], &dq_buffer_.get()[dq_filter_size_ * 7], 0);
}
updateDQFilter(state);
std::array<double, 7> tau_J_d;
for (size_t i = 0; i < 7; i++) {
tau_J_d[i] = K_P_[i] * (state.
q_d[i] - state.
q[i]) + K_D_[i] * (dq_d_[i] - getDQFiltered(i));
}
return tau_J_d;
}
for (size_t i = 0; i < 7; i++) {
dq_buffer_.get()[dq_current_filter_position_ * 7 + i] = state.
dq[i];
}
dq_current_filter_position_ = (dq_current_filter_position_ + 1) % dq_filter_size_;
}
double getDQFiltered(size_t index) const {
double value = 0;
for (size_t i = index; i < 7 * dq_filter_size_; i += 7) {
value += dq_buffer_.get()[i];
}
return value / dq_filter_size_;
}
private:
size_t dq_current_filter_position_;
size_t dq_filter_size_;
const std::array<double, 7> K_P_;
const std::array<double, 7> K_D_;
std::array<double, 7> dq_d_;
std::unique_ptr<double[]> dq_buffer_;
};
std::vector<double> generateTrajectory(double a_max) {
std::vector<double> trajectory;
constexpr double kTimeStep = 0.001;
constexpr double kAccelerationTime = 1;
constexpr double kConstantVelocityTime = 1;
double a = 0;
double v = 0;
double t = 0;
while (t < (2 * kAccelerationTime + kConstantVelocityTime)) {
if (t <= kAccelerationTime) {
a = pow(sin(t * M_PI / kAccelerationTime), 2) * a_max;
} else if (t <= (kAccelerationTime + kConstantVelocityTime)) {
a = 0;
} else {
const double deceleration_time =
(kAccelerationTime + kConstantVelocityTime) - t;
a = -pow(sin(deceleration_time * M_PI / kAccelerationTime), 2) * a_max;
}
v += a * kTimeStep;
t += kTimeStep;
trajectory.push_back(v);
}
return trajectory;
}
}
void writeLogToFile(const std::vector<franka::Record>& log);
int main(int argc, char** argv) {
if (argc != 2) {
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
return -1;
}
const size_t joint_number{3};
const size_t filter_size{5};
const std::array<double, 7> K_P{{200.0, 200.0, 200.0, 200.0, 200.0, 200.0, 200.0}};
const std::array<double, 7> K_D{{10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0}};
const double max_acceleration{1.0};
Controller controller(filter_size, K_P, K_D);
try {
setDefaultBehavior(robot);
std::array<double, 7> q_goal = {{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
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;
robot.setCollisionBehavior(
{{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}});
size_t index = 0;
std::vector<double> trajectory = generateTrajectory(max_acceleration);
return controller.step(robot_state);
};
index += period.toMSec();
if (index >= trajectory.size()) {
index = trajectory.size() - 1;
}
velocities.
dq[joint_number] = trajectory[index];
if (index >= trajectory.size() - 1) {
}
return velocities;
};
bool motion_finished = false;
auto active_control = robot.startJointVelocityControl(
research_interface::robot::Move::ControllerMode::kExternalController);
while (!motion_finished) {
auto read_once_return = active_control->readOnce();
auto robot_state = read_once_return.first;
auto duration = read_once_return.second;
auto cartesian_velocities = callback_motion_generator(robot_state, duration);
auto torques = callback_control(robot_state, duration);
motion_finished = cartesian_velocities.motion_finished;
active_control->writeOnce(cartesian_velocities, torques);
}
std::cout << e.what() << std::endl;
return -1;
std::cout << e.what() << std::endl;
return -1;
}
return 0;
}
void writeLogToFile(const std::vector<franka::Record>& log) {
if (log.empty()) {
return;
}
try {
Poco::Path temp_dir_path(Poco::Path::temp());
temp_dir_path.pushDirectory("libfranka-logs");
Poco::File temp_dir(temp_dir_path);
temp_dir.createDirectories();
std::string now_string =
Poco::DateTimeFormatter::format(Poco::Timestamp{}, "%Y-%m-%d-%h-%m-%S-%i");
std::string filename = std::string{"log-" + now_string + ".csv"};
Poco::File log_file(Poco::Path(temp_dir_path, filename));
if (!log_file.createFile()) {
std::cout << "Failed to write log file." << std::endl;
return;
}
std::ofstream log_stream(log_file.path().c_str());
std::cout << "Log file written to: " << log_file.path() << std::endl;
} catch (...) {
std::cout << "Failed to write log file." << std::endl;
}
}
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
std::array< double, 7 > dq
Desired joint velocities in .
Definition control_types.h:121
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition robot.h:68
Stores joint-level torque commands without gravity and friction.
Definition control_types.h:45
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition control_types.h:294
Contains common types and functions for the examples.
Contains exception definitions.
std::string logToCSV(const std::vector< Record > &log)
Writes the log to a string in CSV format.
Contains the franka::Robot type.
ControlException is thrown if an error occurs during motion generation or torque control.
Definition exception.h:73
const std::vector< franka::Record > log
Vector of states and commands logged just before the exception occurred.
Definition exception.h:85
Base class for all exceptions used by libfranka.
Definition exception.h:20
Describes the robot state.
Definition robot_state.h:34
std::array< double, 7 > q_d
Desired joint position.
Definition robot_state.h:239
std::array< double, 7 > q
Measured joint position.
Definition robot_state.h:233
std::array< double, 7 > dq
Measured joint velocity.
Definition robot_state.h:245