mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 18:10:47 +02:00
Clang-format run
This commit is contained in:
@@ -1,14 +1,9 @@
|
||||
#include <cmath>
|
||||
#include "ur_modern_driver/ros/action_server.h"
|
||||
#include <cmath>
|
||||
|
||||
ActionServer::ActionServer(TrajectoryFollower& follower, std::vector<std::string>& joint_names, double max_velocity)
|
||||
: as_(
|
||||
nh_,
|
||||
"follow_joint_trajectory",
|
||||
boost::bind(&ActionServer::onGoal, this, _1),
|
||||
boost::bind(&ActionServer::onCancel, this, _1),
|
||||
false
|
||||
)
|
||||
: as_(nh_, "follow_joint_trajectory", boost::bind(&ActionServer::onGoal, this, _1),
|
||||
boost::bind(&ActionServer::onCancel, this, _1), false)
|
||||
, joint_names_(joint_names)
|
||||
, joint_set_(joint_names.begin(), joint_names.end())
|
||||
, max_velocity_(max_velocity)
|
||||
@@ -22,7 +17,7 @@ ActionServer::ActionServer(TrajectoryFollower& follower, std::vector<std::string
|
||||
|
||||
void ActionServer::start()
|
||||
{
|
||||
if(running_)
|
||||
if (running_)
|
||||
return;
|
||||
|
||||
LOG_INFO("Starting ActionServer");
|
||||
@@ -35,23 +30,23 @@ void ActionServer::onRobotStateChange(RobotState state)
|
||||
{
|
||||
state_ = state;
|
||||
|
||||
//don't interrupt if everything is fine
|
||||
if(state == RobotState::Running)
|
||||
// don't interrupt if everything is fine
|
||||
if (state == RobotState::Running)
|
||||
return;
|
||||
|
||||
//don't retry interrupts
|
||||
if(interrupt_traj_ || !has_goal_)
|
||||
// don't retry interrupts
|
||||
if (interrupt_traj_ || !has_goal_)
|
||||
return;
|
||||
|
||||
//on successful lock we're not executing a goal so don't interrupt
|
||||
if(tj_mutex_.try_lock())
|
||||
// on successful lock we're not executing a goal so don't interrupt
|
||||
if (tj_mutex_.try_lock())
|
||||
{
|
||||
tj_mutex_.unlock();
|
||||
return;
|
||||
}
|
||||
|
||||
interrupt_traj_ = true;
|
||||
//wait for goal to be interrupted and automagically unlock when going out of scope
|
||||
// wait for goal to be interrupted and automagically unlock when going out of scope
|
||||
std::lock_guard<std::mutex> lock(tj_mutex_);
|
||||
|
||||
Result res;
|
||||
@@ -60,7 +55,6 @@ void ActionServer::onRobotStateChange(RobotState state)
|
||||
curr_gh_.setAborted(res, res.error_string);
|
||||
}
|
||||
|
||||
|
||||
bool ActionServer::updateState(RTShared& data)
|
||||
{
|
||||
q_actual_ = data.q_actual;
|
||||
@@ -68,7 +62,6 @@ bool ActionServer::updateState(RTShared& data)
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool ActionServer::consume(RTState_V1_6__7& state)
|
||||
{
|
||||
return updateState(state);
|
||||
@@ -86,7 +79,6 @@ bool ActionServer::consume(RTState_V3_2__3& state)
|
||||
return updateState(state);
|
||||
}
|
||||
|
||||
|
||||
void ActionServer::onGoal(GoalHandle gh)
|
||||
{
|
||||
Result res;
|
||||
@@ -94,7 +86,7 @@ void ActionServer::onGoal(GoalHandle gh)
|
||||
|
||||
LOG_INFO("Received new goal");
|
||||
|
||||
if(!validate(gh, res) || !try_execute(gh, res))
|
||||
if (!validate(gh, res) || !try_execute(gh, res))
|
||||
{
|
||||
LOG_WARN("Goal error: %s", res.error_string.c_str());
|
||||
gh.setRejected(res, res.error_string);
|
||||
@@ -104,7 +96,7 @@ void ActionServer::onGoal(GoalHandle gh)
|
||||
void ActionServer::onCancel(GoalHandle gh)
|
||||
{
|
||||
interrupt_traj_ = true;
|
||||
//wait for goal to be interrupted
|
||||
// wait for goal to be interrupted
|
||||
std::lock_guard<std::mutex> lock(tj_mutex_);
|
||||
|
||||
Result res;
|
||||
@@ -114,22 +106,22 @@ void ActionServer::onCancel(GoalHandle gh)
|
||||
}
|
||||
|
||||
bool ActionServer::validate(GoalHandle& gh, Result& res)
|
||||
{
|
||||
{
|
||||
return validateState(gh, res) && validateJoints(gh, res) && validateTrajectory(gh, res);
|
||||
}
|
||||
|
||||
bool ActionServer::validateState(GoalHandle& gh, Result& res)
|
||||
{
|
||||
switch(state_)
|
||||
switch (state_)
|
||||
{
|
||||
case RobotState::EmergencyStopped:
|
||||
res.error_string = "Robot is emergency stopped";
|
||||
return false;
|
||||
|
||||
|
||||
case RobotState::ProtectiveStopped:
|
||||
res.error_string = "Robot is protective stopped";
|
||||
return false;
|
||||
|
||||
|
||||
case RobotState::Error:
|
||||
res.error_string = "Robot is not ready, check robot_mode";
|
||||
return false;
|
||||
@@ -149,7 +141,7 @@ bool ActionServer::validateJoints(GoalHandle& gh, Result& res)
|
||||
auto const& joints = goal->trajectory.joint_names;
|
||||
std::set<std::string> goal_joints(joints.begin(), joints.end());
|
||||
|
||||
if(goal_joints == joint_set_)
|
||||
if (goal_joints == joint_set_)
|
||||
return true;
|
||||
|
||||
res.error_code = Result::INVALID_JOINTS;
|
||||
@@ -162,42 +154,42 @@ bool ActionServer::validateTrajectory(GoalHandle& gh, Result& res)
|
||||
auto goal = gh.getGoal();
|
||||
res.error_code = Result::INVALID_GOAL;
|
||||
|
||||
//must at least have one point
|
||||
if(goal->trajectory.points.size() < 1)
|
||||
// must at least have one point
|
||||
if (goal->trajectory.points.size() < 1)
|
||||
return false;
|
||||
|
||||
for(auto const& point : goal->trajectory.points)
|
||||
for (auto const& point : goal->trajectory.points)
|
||||
{
|
||||
if(point.velocities.size() != joint_names_.size())
|
||||
if (point.velocities.size() != joint_names_.size())
|
||||
{
|
||||
res.error_code = Result::INVALID_GOAL;
|
||||
res.error_string = "Received a goal with an invalid number of velocities";
|
||||
return false;
|
||||
}
|
||||
|
||||
if(point.positions.size() != joint_names_.size())
|
||||
|
||||
if (point.positions.size() != joint_names_.size())
|
||||
{
|
||||
res.error_code = Result::INVALID_GOAL;
|
||||
res.error_string = "Received a goal with an invalid number of positions";
|
||||
return false;
|
||||
}
|
||||
|
||||
for(auto const& velocity : point.velocities)
|
||||
|
||||
for (auto const& velocity : point.velocities)
|
||||
{
|
||||
if(!std::isfinite(velocity))
|
||||
if (!std::isfinite(velocity))
|
||||
{
|
||||
res.error_string = "Received a goal with infinities or NaNs in velocity";
|
||||
return false;
|
||||
}
|
||||
if(std::fabs(velocity) > max_velocity_)
|
||||
if (std::fabs(velocity) > max_velocity_)
|
||||
{
|
||||
res.error_string = "Received a goal with velocities that are higher than " + std::to_string(max_velocity_);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
for(auto const& position : point.positions)
|
||||
for (auto const& position : point.positions)
|
||||
{
|
||||
if(!std::isfinite(position))
|
||||
if (!std::isfinite(position))
|
||||
{
|
||||
res.error_string = "Received a goal with infinities or NaNs in positions";
|
||||
return false;
|
||||
@@ -205,34 +197,34 @@ bool ActionServer::validateTrajectory(GoalHandle& gh, Result& res)
|
||||
}
|
||||
}
|
||||
|
||||
//todo validate start position?
|
||||
// todo validate start position?
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
inline std::chrono::microseconds convert(const ros::Duration &dur)
|
||||
inline std::chrono::microseconds convert(const ros::Duration& dur)
|
||||
{
|
||||
return std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::seconds(dur.sec) +
|
||||
std::chrono::nanoseconds(dur.nsec));
|
||||
std::chrono::nanoseconds(dur.nsec));
|
||||
}
|
||||
|
||||
bool ActionServer::try_execute(GoalHandle& gh, Result& res)
|
||||
{
|
||||
if(!running_)
|
||||
if (!running_)
|
||||
{
|
||||
res.error_string = "Internal error";
|
||||
return false;
|
||||
}
|
||||
if(!tj_mutex_.try_lock())
|
||||
if (!tj_mutex_.try_lock())
|
||||
{
|
||||
interrupt_traj_ = true;
|
||||
res.error_string = "Received another trajectory";
|
||||
curr_gh_.setAborted(res, res.error_string);
|
||||
tj_mutex_.lock();
|
||||
//todo: make configurable
|
||||
// todo: make configurable
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(250));
|
||||
}
|
||||
//locked here
|
||||
// locked here
|
||||
curr_gh_ = gh;
|
||||
interrupt_traj_ = false;
|
||||
has_goal_ = true;
|
||||
@@ -244,12 +236,12 @@ bool ActionServer::try_execute(GoalHandle& gh, Result& res)
|
||||
std::vector<size_t> ActionServer::reorderMap(std::vector<std::string> goal_joints)
|
||||
{
|
||||
std::vector<size_t> indecies;
|
||||
for(auto const& aj : joint_names_)
|
||||
for (auto const& aj : joint_names_)
|
||||
{
|
||||
size_t j = 0;
|
||||
for(auto const& gj : goal_joints)
|
||||
for (auto const& gj : goal_joints)
|
||||
{
|
||||
if(aj == gj)
|
||||
if (aj == gj)
|
||||
break;
|
||||
j++;
|
||||
}
|
||||
@@ -261,40 +253,40 @@ std::vector<size_t> ActionServer::reorderMap(std::vector<std::string> goal_joint
|
||||
void ActionServer::trajectoryThread()
|
||||
{
|
||||
LOG_INFO("Trajectory thread started");
|
||||
|
||||
while(running_)
|
||||
|
||||
while (running_)
|
||||
{
|
||||
std::unique_lock<std::mutex> lk(tj_mutex_);
|
||||
if(!tj_cv_.wait_for(lk, std::chrono::milliseconds(100), [&]{return running_ && has_goal_;}))
|
||||
if (!tj_cv_.wait_for(lk, std::chrono::milliseconds(100), [&] { return running_ && has_goal_; }))
|
||||
continue;
|
||||
|
||||
|
||||
LOG_INFO("Trajectory received and accepted");
|
||||
curr_gh_.setAccepted();
|
||||
|
||||
auto goal = curr_gh_.getGoal();
|
||||
std::vector<TrajectoryPoint> trajectory;
|
||||
trajectory.reserve(goal->trajectory.points.size()+1);
|
||||
trajectory.reserve(goal->trajectory.points.size() + 1);
|
||||
|
||||
//joint names of the goal might have a different ordering compared
|
||||
//to what URScript expects so need to map between the two
|
||||
// joint names of the goal might have a different ordering compared
|
||||
// to what URScript expects so need to map between the two
|
||||
auto mapping = reorderMap(goal->trajectory.joint_names);
|
||||
|
||||
|
||||
LOG_INFO("Translating trajectory");
|
||||
|
||||
auto const& fp = goal->trajectory.points[0];
|
||||
auto fpt = convert(fp.time_from_start);
|
||||
|
||||
//make sure we have a proper t0 position
|
||||
if(fpt > std::chrono::microseconds(0))
|
||||
// make sure we have a proper t0 position
|
||||
if (fpt > std::chrono::microseconds(0))
|
||||
{
|
||||
LOG_INFO("Trajectory without t0 recieved, inserting t0 at currrent position");
|
||||
trajectory.push_back(TrajectoryPoint(q_actual_, qd_actual_, std::chrono::microseconds(0)));
|
||||
}
|
||||
|
||||
for(auto const& point : goal->trajectory.points)
|
||||
for (auto const& point : goal->trajectory.points)
|
||||
{
|
||||
std::array<double, 6> pos, vel;
|
||||
for(size_t i = 0; i < 6; i++)
|
||||
for (size_t i = 0; i < 6; i++)
|
||||
{
|
||||
size_t idx = mapping[i];
|
||||
pos[idx] = point.positions[i];
|
||||
@@ -304,17 +296,19 @@ void ActionServer::trajectoryThread()
|
||||
trajectory.push_back(TrajectoryPoint(pos, vel, t));
|
||||
}
|
||||
|
||||
double t = std::chrono::duration_cast<std::chrono::duration<double>>(trajectory[trajectory.size()-1].time_from_start).count();
|
||||
double t =
|
||||
std::chrono::duration_cast<std::chrono::duration<double>>(trajectory[trajectory.size() - 1].time_from_start)
|
||||
.count();
|
||||
LOG_INFO("Executing trajectory with %zu points and duration of %4.3fs", trajectory.size(), t);
|
||||
|
||||
Result res;
|
||||
|
||||
if(follower_.start())
|
||||
if (follower_.start())
|
||||
{
|
||||
if(follower_.execute(trajectory, interrupt_traj_))
|
||||
if (follower_.execute(trajectory, interrupt_traj_))
|
||||
{
|
||||
//interrupted goals must be handled by interrupt trigger
|
||||
if(!interrupt_traj_)
|
||||
// interrupted goals must be handled by interrupt trigger
|
||||
if (!interrupt_traj_)
|
||||
{
|
||||
LOG_INFO("Trajectory executed successfully");
|
||||
res.error_code = Result::SUCCESSFUL;
|
||||
@@ -327,7 +321,7 @@ void ActionServer::trajectoryThread()
|
||||
{
|
||||
LOG_INFO("Trajectory failed");
|
||||
res.error_code = -100;
|
||||
res.error_string = "Connection to robot was lost";
|
||||
res.error_string = "Connection to robot was lost";
|
||||
curr_gh_.setAborted(res, res.error_string);
|
||||
}
|
||||
|
||||
@@ -337,7 +331,7 @@ void ActionServer::trajectoryThread()
|
||||
{
|
||||
LOG_ERROR("Failed to start trajectory follower!");
|
||||
res.error_code = -100;
|
||||
res.error_string = "Robot connection could not be established";
|
||||
res.error_string = "Robot connection could not be established";
|
||||
curr_gh_.setAborted(res, res.error_string);
|
||||
}
|
||||
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
#include "ur_modern_driver/ros/controller.h"
|
||||
|
||||
ROSController::ROSController(URCommander &commander, TrajectoryFollower& follower, std::vector<std::string> &joint_names, double max_vel_change)
|
||||
ROSController::ROSController(URCommander& commander, TrajectoryFollower& follower,
|
||||
std::vector<std::string>& joint_names, double max_vel_change)
|
||||
: controller_(this, nh_)
|
||||
, joint_interface_(joint_names)
|
||||
, wrench_interface_()
|
||||
@@ -18,7 +19,8 @@ void ROSController::setupConsumer()
|
||||
lastUpdate_ = ros::Time::now();
|
||||
}
|
||||
|
||||
void ROSController::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list, const std::list<hardware_interface::ControllerInfo>& stop_list)
|
||||
void ROSController::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
|
||||
const std::list<hardware_interface::ControllerInfo>& stop_list)
|
||||
{
|
||||
LOG_INFO("Switching hardware interface");
|
||||
|
||||
@@ -60,7 +62,7 @@ void ROSController::reset()
|
||||
{
|
||||
if (active_interface_ == nullptr)
|
||||
return;
|
||||
|
||||
|
||||
active_interface_->reset();
|
||||
}
|
||||
|
||||
@@ -70,7 +72,6 @@ void ROSController::read(RTShared& packet)
|
||||
wrench_interface_.update(packet);
|
||||
}
|
||||
|
||||
|
||||
bool ROSController::update(RTShared& state)
|
||||
{
|
||||
auto time = ros::Time::now();
|
||||
@@ -80,16 +81,16 @@ bool ROSController::update(RTShared& state)
|
||||
read(state);
|
||||
controller_.update(time, diff, !service_enabled_);
|
||||
|
||||
//emergency stop and such should not kill the pipeline
|
||||
//but still prevent writes
|
||||
if(!service_enabled_)
|
||||
// emergency stop and such should not kill the pipeline
|
||||
// but still prevent writes
|
||||
if (!service_enabled_)
|
||||
{
|
||||
reset();
|
||||
return true;
|
||||
}
|
||||
|
||||
//allow the controller to update x times before allowing writes again
|
||||
if(service_cooldown_ > 0)
|
||||
|
||||
// allow the controller to update x times before allowing writes again
|
||||
if (service_cooldown_ > 0)
|
||||
{
|
||||
service_cooldown_ -= 1;
|
||||
return true;
|
||||
@@ -101,9 +102,9 @@ bool ROSController::update(RTShared& state)
|
||||
void ROSController::onRobotStateChange(RobotState state)
|
||||
{
|
||||
bool next = (state == RobotState::Running);
|
||||
if(next == service_enabled_)
|
||||
if (next == service_enabled_)
|
||||
return;
|
||||
|
||||
|
||||
service_enabled_ = next;
|
||||
service_cooldown_ = 125;
|
||||
service_cooldown_ = 125;
|
||||
}
|
||||
@@ -19,14 +19,15 @@ void JointInterface::update(RTShared &packet)
|
||||
WrenchInterface::WrenchInterface()
|
||||
{
|
||||
registerHandle(hardware_interface::ForceTorqueSensorHandle("wrench", "", tcp_.begin(), tcp_.begin() + 3));
|
||||
}
|
||||
}
|
||||
|
||||
void WrenchInterface::update(RTShared &packet)
|
||||
{
|
||||
tcp_ = packet.tcp_force;
|
||||
}
|
||||
|
||||
VelocityInterface::VelocityInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface, std::vector<std::string> &joint_names, double max_vel_change)
|
||||
VelocityInterface::VelocityInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface,
|
||||
std::vector<std::string> &joint_names, double max_vel_change)
|
||||
: commander_(commander), max_vel_change_(max_vel_change)
|
||||
{
|
||||
for (size_t i = 0; i < 6; i++)
|
||||
@@ -50,14 +51,15 @@ bool VelocityInterface::write()
|
||||
|
||||
void VelocityInterface::reset()
|
||||
{
|
||||
for(auto &val : prev_velocity_cmd_)
|
||||
for (auto &val : prev_velocity_cmd_)
|
||||
{
|
||||
val = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
PositionInterface:: PositionInterface(TrajectoryFollower& follower, hardware_interface::JointStateInterface &js_interface, std::vector<std::string> &joint_names)
|
||||
PositionInterface::PositionInterface(TrajectoryFollower &follower,
|
||||
hardware_interface::JointStateInterface &js_interface,
|
||||
std::vector<std::string> &joint_names)
|
||||
: follower_(follower)
|
||||
{
|
||||
for (size_t i = 0; i < 6; i++)
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
#include "ur_modern_driver/ros/mb_publisher.h"
|
||||
|
||||
inline void appendAnalog(std::vector<ur_msgs::Analog> &vec, double val, uint8_t pin)
|
||||
inline void appendAnalog(std::vector<ur_msgs::Analog>& vec, double val, uint8_t pin)
|
||||
{
|
||||
ur_msgs::Analog ana;
|
||||
ana.pin = pin;
|
||||
@@ -8,7 +8,7 @@ inline void appendAnalog(std::vector<ur_msgs::Analog> &vec, double val, uint8_t
|
||||
vec.push_back(ana);
|
||||
}
|
||||
|
||||
void MBPublisher::publish(ur_msgs::IOStates &io_msg, SharedMasterBoardData& data)
|
||||
void MBPublisher::publish(ur_msgs::IOStates& io_msg, SharedMasterBoardData& data)
|
||||
{
|
||||
appendAnalog(io_msg.analog_in_states, data.analog_input0, 0);
|
||||
appendAnalog(io_msg.analog_in_states, data.analog_input1, 1);
|
||||
|
||||
@@ -5,10 +5,9 @@ ServiceStopper::ServiceStopper(std::vector<Service*> services)
|
||||
, services_(services)
|
||||
, last_state_(RobotState::Error)
|
||||
{
|
||||
//enable_all();
|
||||
// enable_all();
|
||||
}
|
||||
|
||||
|
||||
bool ServiceStopper::enableCallback(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& resp)
|
||||
{
|
||||
notify_all(RobotState::Running);
|
||||
@@ -17,10 +16,10 @@ bool ServiceStopper::enableCallback(std_srvs::EmptyRequest& req, std_srvs::Empty
|
||||
|
||||
void ServiceStopper::notify_all(RobotState state)
|
||||
{
|
||||
if(last_state_ == state)
|
||||
if (last_state_ == state)
|
||||
return;
|
||||
|
||||
for(auto const service : services_)
|
||||
|
||||
for (auto const service : services_)
|
||||
{
|
||||
service->onRobotStateChange(state);
|
||||
}
|
||||
@@ -30,15 +29,15 @@ void ServiceStopper::notify_all(RobotState state)
|
||||
|
||||
bool ServiceStopper::handle(SharedRobotModeData& data, bool error)
|
||||
{
|
||||
if(data.emergency_stopped)
|
||||
if (data.emergency_stopped)
|
||||
{
|
||||
notify_all(RobotState::EmergencyStopped);
|
||||
}
|
||||
else if(data.protective_stopped)
|
||||
else if (data.protective_stopped)
|
||||
{
|
||||
notify_all(RobotState::ProtectiveStopped);
|
||||
}
|
||||
else if(error)
|
||||
else if (error)
|
||||
{
|
||||
notify_all(RobotState::Error);
|
||||
}
|
||||
|
||||
@@ -1,8 +1,7 @@
|
||||
#include <cmath>
|
||||
#include <endian.h>
|
||||
#include "ur_modern_driver/ros/trajectory_follower.h"
|
||||
|
||||
|
||||
#include <endian.h>
|
||||
#include <cmath>
|
||||
|
||||
static const int32_t MULT_JOINTSTATE_ = 1000000;
|
||||
static const std::string JOINT_STATE_REPLACE("{{JOINT_STATE_REPLACE}}");
|
||||
static const std::string SERVO_J_REPLACE("{{SERVO_J_REPLACE}}");
|
||||
@@ -65,7 +64,8 @@ def driverProg():
|
||||
end
|
||||
)";
|
||||
|
||||
TrajectoryFollower::TrajectoryFollower(URCommander &commander, std::string& reverse_ip, int reverse_port, bool version_3)
|
||||
TrajectoryFollower::TrajectoryFollower(URCommander &commander, std::string &reverse_ip, int reverse_port,
|
||||
bool version_3)
|
||||
: running_(false)
|
||||
, commander_(commander)
|
||||
, server_(reverse_port)
|
||||
@@ -77,13 +77,12 @@ TrajectoryFollower::TrajectoryFollower(URCommander &commander, std::string& reve
|
||||
ros::param::get("~servoj_lookahead_time", servoj_lookahead_time_);
|
||||
ros::param::get("~servoj_gain", servoj_gain_);
|
||||
|
||||
|
||||
std::string res(POSITION_PROGRAM);
|
||||
res.replace(res.find(JOINT_STATE_REPLACE), JOINT_STATE_REPLACE.length(), std::to_string(MULT_JOINTSTATE_));
|
||||
|
||||
std::ostringstream out;
|
||||
out << "t=" << std::fixed << std::setprecision(4) << servoj_time_;
|
||||
if(version_3)
|
||||
if (version_3)
|
||||
out << ", lookahead_time=" << servoj_lookahead_time_ << ", gain=" << servoj_gain_;
|
||||
|
||||
res.replace(res.find(SERVO_J_REPLACE), SERVO_J_REPLACE.length(), out.str());
|
||||
@@ -91,21 +90,21 @@ TrajectoryFollower::TrajectoryFollower(URCommander &commander, std::string& reve
|
||||
res.replace(res.find(SERVER_PORT_REPLACE), SERVER_PORT_REPLACE.length(), std::to_string(reverse_port));
|
||||
program_ = res;
|
||||
|
||||
if(!server_.bind())
|
||||
if (!server_.bind())
|
||||
{
|
||||
LOG_ERROR("Failed to bind server, the port %d is likely already in use", reverse_port);
|
||||
std::exit(-1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool TrajectoryFollower::start()
|
||||
{
|
||||
if(running_)
|
||||
return true; //not sure
|
||||
if (running_)
|
||||
return true; // not sure
|
||||
|
||||
LOG_INFO("Uploading trajectory program to robot");
|
||||
|
||||
if(!commander_.uploadProg(program_))
|
||||
|
||||
if (!commander_.uploadProg(program_))
|
||||
{
|
||||
LOG_ERROR("Program upload failed!");
|
||||
return false;
|
||||
@@ -113,29 +112,30 @@ bool TrajectoryFollower::start()
|
||||
|
||||
LOG_DEBUG("Awaiting incomming robot connection");
|
||||
|
||||
if(!server_.accept())
|
||||
if (!server_.accept())
|
||||
{
|
||||
LOG_ERROR("Failed to accept incomming robot connection");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
LOG_DEBUG("Robot successfully connected");
|
||||
return (running_ = true);
|
||||
}
|
||||
|
||||
bool TrajectoryFollower::execute(std::array<double, 6> &positions, bool keep_alive)
|
||||
{
|
||||
if(!running_)
|
||||
if (!running_)
|
||||
return false;
|
||||
|
||||
// LOG_INFO("servoj([%f,%f,%f,%f,%f,%f])", positions[0], positions[1], positions[2], positions[3], positions[4], positions[5]);
|
||||
// LOG_INFO("servoj([%f,%f,%f,%f,%f,%f])", positions[0], positions[1], positions[2], positions[3], positions[4],
|
||||
// positions[5]);
|
||||
|
||||
last_positions_ = positions;
|
||||
|
||||
uint8_t buf[sizeof(uint32_t)*7];
|
||||
uint8_t buf[sizeof(uint32_t) * 7];
|
||||
uint8_t *idx = buf;
|
||||
|
||||
for(auto const& pos : positions)
|
||||
|
||||
for (auto const &pos : positions)
|
||||
{
|
||||
int32_t val = static_cast<int32_t>(pos * MULT_JOINTSTATE_);
|
||||
val = htobe32(val);
|
||||
@@ -145,7 +145,7 @@ bool TrajectoryFollower::execute(std::array<double, 6> &positions, bool keep_ali
|
||||
int32_t val = htobe32(static_cast<int32_t>(keep_alive));
|
||||
append(idx, val);
|
||||
|
||||
size_t written;
|
||||
size_t written;
|
||||
return server_.write(buf, sizeof(buf), written);
|
||||
}
|
||||
|
||||
@@ -166,60 +166,54 @@ bool TrajectoryFollower::execute(std::array<double, 6> &positions)
|
||||
|
||||
bool TrajectoryFollower::execute(std::vector<TrajectoryPoint> &trajectory, std::atomic<bool> &interrupt)
|
||||
{
|
||||
if(!running_)
|
||||
if (!running_)
|
||||
return false;
|
||||
|
||||
|
||||
using namespace std::chrono;
|
||||
typedef duration<double> double_seconds;
|
||||
typedef high_resolution_clock Clock;
|
||||
typedef Clock::time_point Time;
|
||||
|
||||
auto& last = trajectory[trajectory.size()-1];
|
||||
auto& prev = trajectory[0];
|
||||
auto &last = trajectory[trajectory.size() - 1];
|
||||
auto &prev = trajectory[0];
|
||||
|
||||
Time t0 = Clock::now();
|
||||
Time latest = t0;
|
||||
|
||||
std::array<double, 6> positions;
|
||||
|
||||
for(auto const& point : trajectory)
|
||||
for (auto const &point : trajectory)
|
||||
{
|
||||
//skip t0
|
||||
if(&point == &prev)
|
||||
// skip t0
|
||||
if (&point == &prev)
|
||||
continue;
|
||||
|
||||
if(interrupt)
|
||||
if (interrupt)
|
||||
break;
|
||||
|
||||
auto duration = point.time_from_start - prev.time_from_start;
|
||||
double d_s = duration_cast<double_seconds>(duration).count();
|
||||
|
||||
//interpolation loop
|
||||
while(!interrupt)
|
||||
// interpolation loop
|
||||
while (!interrupt)
|
||||
{
|
||||
latest = Clock::now();
|
||||
auto elapsed = latest - t0;
|
||||
|
||||
if(point.time_from_start <= elapsed)
|
||||
if (point.time_from_start <= elapsed)
|
||||
break;
|
||||
|
||||
if(last.time_from_start <= elapsed)
|
||||
if (last.time_from_start <= elapsed)
|
||||
return true;
|
||||
|
||||
double elapsed_s = duration_cast<double_seconds>(elapsed - prev.time_from_start).count();
|
||||
for(size_t j = 0; j < positions.size(); j++)
|
||||
for (size_t j = 0; j < positions.size(); j++)
|
||||
{
|
||||
positions[j] = interpolate(
|
||||
elapsed_s,
|
||||
d_s,
|
||||
prev.positions[j],
|
||||
point.positions[j],
|
||||
prev.velocities[j],
|
||||
point.velocities[j]
|
||||
);
|
||||
positions[j] =
|
||||
interpolate(elapsed_s, d_s, prev.positions[j], point.positions[j], prev.velocities[j], point.velocities[j]);
|
||||
}
|
||||
|
||||
if(!execute(positions, true))
|
||||
if (!execute(positions, true))
|
||||
return false;
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds((int)((servoj_time_ * 1000) / 4.)));
|
||||
@@ -228,20 +222,20 @@ bool TrajectoryFollower::execute(std::vector<TrajectoryPoint> &trajectory, std::
|
||||
prev = point;
|
||||
}
|
||||
|
||||
//In theory it's possible the last position won't be sent by
|
||||
//the interpolation loop above but rather some position between
|
||||
//t[N-1] and t[N] where N is the number of trajectory points.
|
||||
//To make sure this does not happen the last position is sent
|
||||
// In theory it's possible the last position won't be sent by
|
||||
// the interpolation loop above but rather some position between
|
||||
// t[N-1] and t[N] where N is the number of trajectory points.
|
||||
// To make sure this does not happen the last position is sent
|
||||
return execute(last.positions, true);
|
||||
}
|
||||
|
||||
void TrajectoryFollower::stop()
|
||||
{
|
||||
if(!running_)
|
||||
if (!running_)
|
||||
return;
|
||||
|
||||
//std::array<double, 6> empty;
|
||||
//execute(empty, false);
|
||||
// std::array<double, 6> empty;
|
||||
// execute(empty, false);
|
||||
|
||||
server_.disconnectClient();
|
||||
running_ = false;
|
||||
|
||||
Reference in New Issue
Block a user