Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added handler for inverse kinematics special case joint request #240

Merged
merged 66 commits into from
Jun 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
66 commits
Select commit Hold shift + click to select a range
f99d5ae
Added special case for inverse kinematics
Geeoon May 9, 2023
8e97608
Reformat
Geeoon May 16, 2023
e0170e8
Added special case for inverse kinematics
Geeoon May 9, 2023
d5ed1a5
Reformat
Geeoon May 16, 2023
a1d88f7
Added ik global
Geeoon May 16, 2023
03e9c08
Merge branch 'inverse-kinematics-requests' of https://github.com/husk…
Geeoon May 16, 2023
df5d3ba
Renamed arm IK global. made type atomic as well
Geeoon May 17, 2023
b9a89ac
Added armIKEnabled handler and validater
Geeoon May 17, 2023
60d5cd4
Added case for when armIK global is enabled/disabled
Geeoon May 17, 2023
2b75bbe
Fixed build error
Geeoon May 17, 2023
650afcd
Fixed formatting error
Geeoon May 17, 2023
e982ddb
Removed redundant code
Geeoon May 19, 2023
23a3ad6
Set armIKEnabled to false on e stop and connect
Geeoon May 19, 2023
d835d89
Fixed build error
Geeoon May 19, 2023
dc89f9f
Merge remote-tracking branch 'origin' into inverse-kinematics-requests
Geeoon May 20, 2023
ab142c5
Proper namespace for validateKey
Geeoon May 20, 2023
63820f6
Added special case for inverse kinematics
Geeoon May 9, 2023
f1a7df4
Reformat
Geeoon May 16, 2023
4397e15
Added ik global
Geeoon May 16, 2023
4722f2a
Renamed arm IK global. made type atomic as well
Geeoon May 17, 2023
f9082f3
Added armIKEnabled handler and validater
Geeoon May 17, 2023
012e19b
Added case for when armIK global is enabled/disabled
Geeoon May 17, 2023
0741dee
Fixed build error
Geeoon May 17, 2023
3b36cc8
Fixed formatting error
Geeoon May 17, 2023
4a014c0
Removed redundant code
Geeoon May 19, 2023
be99adf
Set armIKEnabled to false on e stop and connect
Geeoon May 19, 2023
320540c
Fixed build error
Geeoon May 19, 2023
885fa66
Proper namespace for validateKey
Geeoon May 20, 2023
c23918b
Merge branch 'inverse-kinematics-requests' of https://github.com/husk…
Geeoon May 22, 2023
389960e
Added special case for inverse kinematics
Geeoon May 9, 2023
d3f9ee8
Reformat
Geeoon May 16, 2023
49bffe0
Added ik global
Geeoon May 16, 2023
3ac206c
Renamed arm IK global. made type atomic as well
Geeoon May 17, 2023
d3fd8c5
Added armIKEnabled handler and validater
Geeoon May 17, 2023
70bf96a
Added case for when armIK global is enabled/disabled
Geeoon May 17, 2023
b0a4ff3
Fixed build error
Geeoon May 17, 2023
f220de6
Fixed formatting error
Geeoon May 17, 2023
93ed75b
Removed redundant code
Geeoon May 19, 2023
edb6b2d
Set armIKEnabled to false on e stop and connect
Geeoon May 19, 2023
3e6dc42
Fixed build error
Geeoon May 19, 2023
23fb7df
Proper namespace for validateKey
Geeoon May 20, 2023
7ac3c1a
Added armIKEnabled handler and validater
Geeoon May 17, 2023
8a36a39
Added case for when armIK global is enabled/disabled
Geeoon May 17, 2023
f0892ed
Fixed build error
Geeoon May 17, 2023
387f9a4
Fixed formatting error
Geeoon May 17, 2023
72ac754
Removed redundant code
Geeoon May 19, 2023
0ecf91b
Proper namespace for validateKey
Geeoon May 20, 2023
6e52f8d
rebase
Geeoon Jun 1, 2023
c1ada24
removed old bool for arm ik enabled
Geeoon Jun 1, 2023
bbb925f
Set setpoint to current ee position on ik enable
Geeoon Jun 1, 2023
86eeb8c
Reformat and crash on no valid data
Geeoon Jun 2, 2023
dbe102a
Reformat
Geeoon Jun 2, 2023
7f3311d
Added updateArmThread
Geeoon Jun 2, 2023
2c22390
Reformat
Geeoon Jun 2, 2023
09d7df7
fix more things
Geeoon Jun 2, 2023
7eeaede
Added scalar to velocity set
Geeoon Jun 3, 2023
e78986a
Addressed some PR comments
Geeoon Jun 3, 2023
350087a
Reformat
Geeoon Jun 3, 2023
a16b9de
Addressed PR comments
Geeoon Jun 3, 2023
1c0355f
Reformat
Geeoon Jun 3, 2023
b012e30
Merge remote-tracking branch 'origin' into inverse-kinematics-requests
Geeoon Jun 3, 2023
9ee7d0a
Addressed PR comments
Geeoon Jun 3, 2023
0a0e67a
fix formatting
abhaybd Jun 4, 2023
d71ae6a
Addressed PR comments
Geeoon Jun 4, 2023
6354a89
Merge remote-tracking branch 'origin' into inverse-kinematics-requests
Geeoon Jun 4, 2023
25cd2f6
Reformat
Geeoon Jun 4, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
42 changes: 36 additions & 6 deletions src/Constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,7 @@ constexpr const char* DGPS_PROTOCOL_NAME = "/dgps";
constexpr const char* ARDUPILOT_PROTOCOL_NAME = "/ardupilot";

constexpr std::chrono::milliseconds JOINT_POWER_REPEAT_PERIOD(333);
constexpr std::chrono::milliseconds ARM_IK_UPDATE_PERIOD(50);

namespace Nav {
// Distance (m) we could have traveled forward in the time it takes to turn 1 radian
Expand Down Expand Up @@ -130,29 +131,58 @@ namespace video {
constexpr int H264_RF_CONSTANT = 40;
} // namespace video

/**
* A map that pairs each of the joints to its corresponding motor.
*/
constexpr frozen::unordered_map<robot::types::jointid_t, robot::types::motorid_t, 7>
JOINT_MOTOR_MAP{{robot::types::jointid_t::armBase, robot::types::motorid_t::armBase},
{robot::types::jointid_t::shoulder, robot::types::motorid_t::shoulder},
{robot::types::jointid_t::elbow, robot::types::motorid_t::elbow},
{robot::types::jointid_t::forearm, robot::types::motorid_t::forearm},
{robot::types::jointid_t::wrist, robot::types::motorid_t::wrist},
{robot::types::jointid_t::hand, robot::types::motorid_t::hand},
{robot::types::jointid_t::activeSuspension,
robot::types::motorid_t::activeSuspension}};
Geeoon marked this conversation as resolved.
Show resolved Hide resolved

// Arm inverse kinematics
namespace arm {

/**
* Maximum commanded end-effector velocity, in m/s
*/
constexpr double MAX_EE_VEL = 0.3;
constexpr double IK_SOLVER_THRESH = 0.001;

constexpr int IK_SOLVER_MAX_ITER = 50;

/**
* The motors used in IK. The ordering in this array is the canonical ordering of these motors
* for IK purposes.
* The joints corresponding to the motors used for IK in the arm. The ordering in this array is
* the canonical ordering of these joints for IK purposes.
*/
constexpr std::array<robot::types::jointid_t, 2> IK_MOTOR_JOINTS = {
robot::types::jointid_t::shoulder, robot::types::jointid_t::elbow};
Geeoon marked this conversation as resolved.
Show resolved Hide resolved

/**
* The motors used in IK. The i-th element in this array corresponds to the joint in the i-th
* element of `IK_MOTOR_JOINTS`
*/
constexpr std::array<robot::types::motorid_t, 2> IK_MOTORS = {
robot::types::motorid_t::shoulder, robot::types::motorid_t::elbow};
constexpr std::array<robot::types::motorid_t, 2> IK_MOTORS = ([]() constexpr {
std::array<robot::types::motorid_t, IK_MOTOR_JOINTS.size()> ret{};
for (size_t i = 0; i < IK_MOTOR_JOINTS.size(); i++) {
ret[i] = JOINT_MOTOR_MAP.at(IK_MOTOR_JOINTS[i]);
}
return ret;
})();

/**
* Map from motor ids to min and max joint limits
* Map from motor ids to min and max joint limits in millidegrees
*/
constexpr frozen::unordered_map<robot::types::motorid_t, std::pair<int, int>, IK_MOTORS.size()>
JOINT_LIMITS{{robot::types::motorid_t::shoulder, {18200, 152500}},
{robot::types::motorid_t::elbow, {-169100, 0}}};

/**
* Map from motor ids to segment length
* Map from motor ids to segment length in meters
*/
constexpr frozen::unordered_map<robot::types::motorid_t, double, IK_MOTORS.size()>
SEGMENT_LENGTHS{{robot::types::motorid_t::shoulder, 0.3848608},
Expand Down
1 change: 1 addition & 0 deletions src/Globals.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,4 +42,5 @@ const kinematics::PlanarArmKinematics<Constants::arm::IK_MOTORS.size()>
planarArmKinematics(getSegLens(), getJointLimits(true), getJointLimits(false),
IK_SOLVER_THRESH, IK_SOLVER_MAX_ITER);
control::PlanarArmController<2> planarArmController({0, 0}, planarArmKinematics);
std::atomic<bool> armIKEnabled = false;
} // namespace Globals
1 change: 1 addition & 0 deletions src/Globals.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,4 +29,5 @@ extern std::atomic<bool> AUTONOMOUS;
extern robot::types::mountedperipheral_t mountedPeripheral;
extern const kinematics::PlanarArmKinematics<2> planarArmKinematics;
extern control::PlanarArmController<2> planarArmController;
extern std::atomic<bool> armIKEnabled;
} // namespace Globals
73 changes: 72 additions & 1 deletion src/network/MissionControlProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ const std::chrono::milliseconds TELEM_REPORT_PERIOD = 100ms;
constexpr const char* EMERGENCY_STOP_REQ_TYPE = "emergencyStopRequest";
constexpr const char* OPERATION_MODE_REQ_TYPE = "operationModeRequest";
constexpr const char* DRIVE_REQ_TYPE = "driveRequest";
constexpr const char* ARM_IK_ENABLED_TYPE = "setArmIKEnabled";
constexpr const char* MOTOR_POWER_REQ_TYPE = "motorPowerRequest";
constexpr const char* JOINT_POWER_REQ_TYPE = "jointPowerRequest";
constexpr const char* MOTOR_POSITION_REQ_TYPE = "motorPositionRequest";
Expand Down Expand Up @@ -82,6 +83,7 @@ void MissionControlProtocol::handleEmergencyStopRequest(const json& j) {
}
// TODO: reinit motors
Globals::E_STOP = stop;
Globals::armIKEnabled = false;
}

static bool validateOperationModeRequest(const json& j) {
Expand All @@ -107,6 +109,10 @@ static bool validateDriveRequest(const json& j) {
util::hasKey(j, "steer") && util::validateRange(j, "steer", -1, 1);
}

static bool validateArmIKEnable(const json& j) {
return util::validateKey(j, "enabled", val_t::boolean);
}

void MissionControlProtocol::handleDriveRequest(const json& j) {
// TODO: ignore this message if we are in autonomous mode.
// fit straight and steer to unit circle; i.e. if |<straight, steer>| > 1, scale each
Expand All @@ -121,6 +127,33 @@ void MissionControlProtocol::handleDriveRequest(const json& j) {
this->setRequestedCmdVel(dtheta, dx);
}

void MissionControlProtocol::handleSetArmIKEnabled(const json& j) {
bool enabled = j["enabled"];
if (enabled) {
Globals::armIKEnabled = false;
if (_arm_ik_repeat_thread.joinable()) {
_arm_ik_repeat_thread.join();
}
navtypes::Vectord<Constants::arm::IK_MOTORS.size()> armJointPositions;
for (size_t i = 0; i < Constants::arm::IK_MOTORS.size(); i++) {
auto positionDataPoint = robot::getMotorPos(Constants::arm::IK_MOTORS[i]);
assert(positionDataPoint.isValid()); // crash if data is not valid
double position = static_cast<double>(positionDataPoint.getData());
position *= M_PI / 180.0 / 1000.0;
armJointPositions(i) = position;
}
Globals::planarArmController.set_setpoint(armJointPositions);
Globals::armIKEnabled = true;
_arm_ik_repeat_thread =
std::thread(&MissionControlProtocol::updateArmIKRepeatTask, this);
} else {
Globals::armIKEnabled = false;
if (_arm_ik_repeat_thread.joinable()) {
_arm_ik_repeat_thread.join();
}
}
}

void MissionControlProtocol::setRequestedCmdVel(double dtheta, double dx) {
{
std::lock_guard<std::mutex> power_lock(this->_joint_power_mutex);
Expand All @@ -132,7 +165,8 @@ void MissionControlProtocol::setRequestedCmdVel(double dtheta, double dx) {
static bool validateJoint(const json& j) {
return util::validateKey(j, "joint", val_t::string) &&
util::validateOneOf(j, "joint",
{"armBase", "shoulder", "elbow", "forearm", "wrist", "hand"});
{"armBase", "shoulder", "elbow", "forearm", "wrist", "hand",
"ikUp", "ikForward"});
}

static bool validateJointPowerRequest(const json& j) {
Expand Down Expand Up @@ -233,6 +267,9 @@ void MissionControlProtocol::sendCameraStreamReport(
}

void MissionControlProtocol::handleConnection() {
// Turn off inverse kinematics on connection
Globals::armIKEnabled = false;

// TODO: send the actual mounted peripheral, as specified by the command-line parameter
json j = {{"type", MOUNTED_PERIPHERAL_REP_TYPE}};

Expand Down Expand Up @@ -289,6 +326,8 @@ void MissionControlProtocol::stopAndShutdownPowerRepeat() {
this->_joint_repeat_thread.join();
}
}
// Turn off inverse kinematics so that IK state will be in sync with mission control
Globals::armIKEnabled = false;
}

MissionControlProtocol::MissionControlProtocol(SingleClientWSServer& server)
Expand All @@ -313,6 +352,14 @@ MissionControlProtocol::MissionControlProtocol(SingleClientWSServer& server)
this->addMessageHandler(DRIVE_REQ_TYPE,
std::bind(&MissionControlProtocol::handleDriveRequest, this, _1),
validateDriveRequest);
this->addMessageHandler(
ARM_IK_ENABLED_TYPE,
std::bind(&MissionControlProtocol::handleSetArmIKEnabled, this, _1),
validateArmIKEnable);
this->addMessageHandler(
ARM_IK_ENABLED_TYPE,
std::bind(&MissionControlProtocol::handleSetArmIKEnabled, this, _1),
validateArmIKEnable);
this->addMessageHandler(
JOINT_POWER_REQ_TYPE,
std::bind(&MissionControlProtocol::handleJointPowerRequest, this, _1),
Expand Down Expand Up @@ -380,6 +427,30 @@ void MissionControlProtocol::jointPowerRepeatTask() {
}
}

void MissionControlProtocol::updateArmIKRepeatTask() {
dataclock::time_point next_update_time = dataclock::now();
while (Globals::armIKEnabled) {
navtypes::Vectord<Constants::arm::IK_MOTORS.size()> armJointPositions;
for (size_t i = 0; i < Constants::arm::IK_MOTORS.size(); i++) {
DataPoint<int32_t> positionDataPoint =
robot::getMotorPos(Constants::arm::IK_MOTORS[i]);
assert(positionDataPoint.isValid()); // crash if data is not valid
double position = static_cast<double>(positionDataPoint.getData());
position *= M_PI / 180.0 / 1000.0;
armJointPositions(i) = position;
}
navtypes::Vectord<Constants::arm::IK_MOTORS.size()> targetJointPositions =
Globals::planarArmController.getCommand(dataclock::now(), armJointPositions);
targetJointPositions /= M_PI / 180.0 / 1000.0; // convert from radians to millidegrees
for (size_t i = 0; i < Constants::arm::IK_MOTORS.size(); i++) {
robot::setMotorPos(Constants::arm::IK_MOTORS[i],
static_cast<int32_t>(targetJointPositions(i)));
}
next_update_time += Constants::ARM_IK_UPDATE_PERIOD;
std::this_thread::sleep_until(next_update_time);
}
}

void MissionControlProtocol::telemReportTask() {
dataclock::time_point pt = dataclock::now();

Expand Down
4 changes: 3 additions & 1 deletion src/network/MissionControlProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ class MissionControlProtocol : public WebSocketProtocol { // TODO: add documenta
private:
void videoStreamTask();
void jointPowerRepeatTask();
void updateArmIKRepeatTask();
void telemReportTask();
SingleClientWSServer& _server;
std::shared_mutex _stream_mutex;
Expand All @@ -55,16 +56,17 @@ class MissionControlProtocol : public WebSocketProtocol { // TODO: add documenta
std::mutex _joint_repeat_thread_mutex;
std::thread _joint_repeat_thread;
std::condition_variable _power_repeat_cv;
std::thread _arm_ik_repeat_thread;
void handleEmergencyStopRequest(const json& j);
void handleOperationModeRequest(const json& j);
void handleCameraStreamOpenRequest(const json& j);
void handleCameraStreamCloseRequest(const json& j);
void handleJointPowerRequest(const json& j);
void handleDriveRequest(const json& j);
void handleSetArmIKEnabled(const json& j);
void sendCameraStreamReport(const CameraID& cam,
const std::vector<std::basic_string<uint8_t>>& videoData);
void sendJointPositionReport(const std::string& jointName, int32_t position);
void sendCameraStreamReport(const CameraID& cam, const std::string& b64_data);
void sendRoverPos();
void handleConnection();
void startPowerRepeat();
Expand Down
4 changes: 4 additions & 0 deletions src/world_interface/data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,10 @@ std::string to_string(robot::types::jointid_t joint) {
return "drillArm";
case jointid_t::activeSuspension:
return "activeSuspension";
case jointid_t::ikUp:
return "ikUp";
case jointid_t::ikForward:
return "ikForward";
default:
// should never happen
return "<unknown>";
Expand Down
11 changes: 8 additions & 3 deletions src/world_interface/data.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,12 +83,15 @@ enum class jointid_t {
wrist,
hand,
drill_arm,
activeSuspension
activeSuspension,
ikForward,
ikUp
};

constexpr auto all_jointid_t = frozen::make_unordered_set<jointid_t>(
{jointid_t::armBase, jointid_t::shoulder, jointid_t::elbow, jointid_t::forearm,
jointid_t::wrist, jointid_t::hand, jointid_t::drill_arm, jointid_t::activeSuspension});
jointid_t::wrist, jointid_t::hand, jointid_t::drill_arm, jointid_t::activeSuspension,
jointid_t::ikForward, jointid_t::ikUp});

constexpr auto name_to_jointid = frozen::make_unordered_map<frozen::string, jointid_t>(
{{"armBase", jointid_t::armBase},
Expand All @@ -98,7 +101,9 @@ constexpr auto name_to_jointid = frozen::make_unordered_map<frozen::string, join
{"wrist", jointid_t::wrist},
{"hand", jointid_t::hand},
{"drillArm", jointid_t::drill_arm},
{"activeSuspension", jointid_t::activeSuspension}});
{"activeSuspension", jointid_t::activeSuspension},
{"ikForward", jointid_t::ikForward},
{"ikUp", jointid_t::ikUp}});

/**
* @brief Represents data measured using a sensor at a given time.
Expand Down
40 changes: 23 additions & 17 deletions src/world_interface/kinematic_common_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,14 +32,6 @@ void setCmdVelToIntegrate(const wheelvel_t& wheelVels) {
}

void setJointMotorPower(robot::types::jointid_t joint, double power);
const std::unordered_map<robot::types::jointid_t, robot::types::motorid_t> jointMotorMap{
{robot::types::jointid_t::armBase, robot::types::motorid_t::armBase},
{robot::types::jointid_t::shoulder, robot::types::motorid_t::shoulder},
{robot::types::jointid_t::elbow, robot::types::motorid_t::elbow},
{robot::types::jointid_t::forearm, robot::types::motorid_t::forearm},
{robot::types::jointid_t::wrist, robot::types::motorid_t::wrist},
{robot::types::jointid_t::hand, robot::types::motorid_t::hand},
{robot::types::jointid_t::activeSuspension, robot::types::motorid_t::activeSuspension}};

std::unordered_map<types::jointid_t, double> jointPowerValues{};
std::mutex jointPowerValuesMutex;
Expand Down Expand Up @@ -106,8 +98,8 @@ void setJointPower(robot::types::jointid_t joint, double power) {

void setJointPos(robot::types::jointid_t joint, int32_t targetPos) {
using robot::types::jointid_t;
if (jointMotorMap.find(joint) != jointMotorMap.end()) {
setMotorPos(jointMotorMap.at(joint), targetPos);
if (Constants::JOINT_MOTOR_MAP.find(joint) != Constants::JOINT_MOTOR_MAP.end()) {
setMotorPos(Constants::JOINT_MOTOR_MAP.at(joint), targetPos);
}
// FIXME: need to do some extra control (probably implementing our own PID control) for the
// differential position, since the potentiometers are giving us joint position instead of
Expand All @@ -129,21 +121,21 @@ void setJointPos(robot::types::jointid_t joint, int32_t targetPos) {
// FIXME: this should ideally never happen, but we don't have support for all joints
// yet because we don't know anything about the drill arm (and need to do extra work
// for the differential)
log(LOG_WARN, "setJointPower called for currently unsupported joint %s\n",
log(LOG_WARN, "setJointPos called for currently unsupported joint %s\n",
util::to_string(joint).c_str());
}
}
types::DataPoint<int32_t> getJointPos(robot::types::jointid_t joint) {
if (jointMotorMap.find(joint) != jointMotorMap.end()) {
return getMotorPos(jointMotorMap.at(joint));
if (Constants::JOINT_MOTOR_MAP.find(joint) != Constants::JOINT_MOTOR_MAP.end()) {
return getMotorPos(Constants::JOINT_MOTOR_MAP.at(joint));
}
// FIXME: need to do some extra work for differential - we will have to figure out which
// motor boards the potentiometers are plugged into and query those for "motor position"
else {
// FIXME: this should ideally never happen, but we don't have support for all joints
// yet because we don't know anything about the drill arm (and need to do extra work
// for the differential)
log(LOG_WARN, "getJointPower called for currently unsupported joint %s\n",
log(LOG_WARN, "getJointPos called for currently unsupported joint %s\n",
util::to_string(joint).c_str());
return {};
}
Expand All @@ -170,9 +162,23 @@ double getJointPowerValue(types::jointid_t joint) {

void setJointMotorPower(robot::types::jointid_t joint, double power) {
using robot::types::jointid_t;

if (jointMotorMap.find(joint) != jointMotorMap.end()) {
setMotorPower(jointMotorMap.at(joint), power);
if (Constants::JOINT_MOTOR_MAP.find(joint) != Constants::JOINT_MOTOR_MAP.end()) {
bool isIKMotor = std::find(Constants::arm::IK_MOTOR_JOINTS.begin(),
Constants::arm::IK_MOTOR_JOINTS.end(),
joint) != Constants::arm::IK_MOTOR_JOINTS.end();
if (!Globals::armIKEnabled || !isIKMotor) {
setMotorPower(Constants::JOINT_MOTOR_MAP.at(joint), power);
}
} else if (joint == jointid_t::ikForward || joint == jointid_t::ikUp) {
if (Globals::armIKEnabled) {
if (joint == jointid_t::ikForward) {
Globals::planarArmController.set_x_vel(dataclock::now(),
power * Constants::arm::MAX_EE_VEL);
} else {
Globals::planarArmController.set_y_vel(dataclock::now(),
power * Constants::arm::MAX_EE_VEL);
}
}
} else {
log(LOG_WARN, "setJointPower called for currently unsupported joint %s\n",
util::to_string(joint).c_str());
Expand Down