Added implementation for scaling joint speeds based on gear ratios#41
Added implementation for scaling joint speeds based on gear ratios#41JackZautner wants to merge 35 commits intoArm_Control_Systemfrom
Conversation
…cations for arm control system
…are into joint-state-publisher-application
…pplication Joint state publisher application
…spect to inheritance
* Starting to implement new design * Continuing implementation, doing simple parts first to remove big issues * Further implementation * Only Differential stuff and mains left * Up to mains complete * Removing old arm motor files, still in VC for reference * Fixed duplicating copies, need to resolve further * Fixed copying by allowing safer copying. Need to double check path planning * All fixed up. Added test script * Additional changes, some motion planning is possible, need to refine motor/encoder directions * Adding direction multipliers to formalize motor reversal in direct speed converters. Need equivalent for differential speed converters. * Updating constants * First autonomous actions on the arm * Adding legend * Adjusting parameters * Tuning joint limits * Feature/over current fault implementation (#31) * Added functionality to retrieve over current status, updated build settings * Added functionality to stop all joints when a motor is over current * Added implementation for action server to stop when an over current fault is detected * set mock arm launch to launch the mock roboclaw * Added functionality to stop the action server when a motor is over current for too long * Fixed code in compliance with PR * Address fix in Motor.cpp * Corresponding const-change in Motor.hpp * Const-correctness in ArmControlActionServer.cpp --------- Co-authored-by: Ben Nowotny <44074469+bennowotny@users.noreply.github.com> * Removed I terms (need synchronization before we can do that) --------- Co-authored-by: Ben Nowotny <bennowotny65535@gmail.com> Co-authored-by: WR-BaseStation <wisconsinrobotics@cae.wisc.edu> Co-authored-by: Ben Nowotny <44074469+bennowotny@users.noreply.github.com>
bennowotny
left a comment
There was a problem hiding this comment.
Additionally, this did not pass hardware testing; the arm was stuttering rather than taking a smooth motion to the target. The cause for this is not apparent, so we may need more testing to find the root cause.
|
I have realized that 1b774df does not explicitly state this but it only contains changes for the direct joint to motor speed converters. |
… meant to go there
…nd joint state publisher to pull correct values from arm params
…os to parameter files
bennowotny
left a comment
There was a problem hiding this comment.
Good work; small edits.
There was a problem hiding this comment.
In simulation, the gear ratio is always 1.
| auto currJoint = goal->trajectory.joint_names.at(i); | ||
|
|
||
| // The position monitor whose velocity is currently being scaled | ||
| auto currPosMtr = namedPositionMonitors.at(currJoint); |
There was a problem hiding this comment.
Avoid copying the std::shared_ptr:
| auto currPosMtr = namedPositionMonitors.at(currJoint); | |
| auto& currPosMtr = *namedPositionMonitors.at(currJoint); |
| #define DIRECT_JOINT_TO_MOTOR_SPEED_CONVERTER_H | ||
|
|
||
| #include "Motor.hpp" | ||
| #include "SingleEncoderJointPositionMonitor.hpp" |
There was a problem hiding this comment.
Include should be unused:
| #include "SingleEncoderJointPositionMonitor.hpp" |
| auto getEncoderConfigFromParams(const XmlRpcValue ¶ms, const std::string &jointName) -> EncoderConfiguration { | ||
| return {.countsPerRotation = static_cast<int32_t>(params[jointName]["counts_per_rotation"]), | ||
| .offset = static_cast<int32_t>(params[jointName]["offset"])}; | ||
| return {.countsPerRotation = static_cast<int32_t>(params[jointName]["encoder_parameters"]["counts_per_rotation"]), | ||
| .offset = static_cast<int32_t>(params[jointName]["encoder_parameters"]["offset"])}; | ||
| } | ||
|
|
||
| auto getMotorConfigFromParams(const XmlRpcValue ¶ms, const std::string &jointName) -> MotorConfiguration { | ||
| return {.gearRatio = static_cast<double>(params[jointName]["motor_configurations"]["gear_ratio"])}; | ||
| } |
There was a problem hiding this comment.
SUGGESTION: Since this is defined in two places the same way, maybe it makes sense to abstract these functions to their own header files and link the implementation in CMake.
There was a problem hiding this comment.
Won't do (for now lol)
|
|
||
| XmlRpcValue encParams; | ||
| pn.getParam("encoder_parameters", encParams); | ||
| XmlRpcValue armParams; | ||
| pn.getParam("arm_parameters", armParams); | ||
|
|
||
| namedJointPositionMonitors.try_emplace("elbowPitch_joint", | ||
|
|
||
| "aux1", | ||
| RoboclawChannel::A, | ||
| getEncoderConfigFromParams(encParams, "elbow"), | ||
| getEncoderConfigFromParams(armParams, "elbow"), | ||
| getMotorConfigFromParams(armParams, "elbow"), | ||
| n); | ||
| namedJointPositionMonitors.try_emplace("elbowRoll_joint", | ||
|
|
||
| "aux1", | ||
| RoboclawChannel::B, | ||
| getEncoderConfigFromParams(encParams, "forearmRoll"), | ||
| getEncoderConfigFromParams(armParams, "forearmRoll"), | ||
| getMotorConfigFromParams(armParams, "forearmRoll"), | ||
| n); | ||
| namedJointPositionMonitors.try_emplace("shoulder_joint", | ||
|
|
||
| "aux0", | ||
| RoboclawChannel::B, | ||
| getEncoderConfigFromParams(encParams, "shoulder"), | ||
| getEncoderConfigFromParams(armParams, "shoulder"), | ||
| getMotorConfigFromParams(armParams, "shoulder"), | ||
| n); | ||
| namedJointPositionMonitors.try_emplace("turntable_joint", | ||
|
|
||
| "aux0", | ||
| RoboclawChannel::A, | ||
| getEncoderConfigFromParams(encParams, "turntable"), | ||
| getEncoderConfigFromParams(armParams, "turntable"), | ||
| getMotorConfigFromParams(armParams, "turntable"), | ||
| n); | ||
| namedJointPositionMonitors.try_emplace("wristPitch_joint", | ||
|
|
||
| "aux2", | ||
| RoboclawChannel::A, | ||
| getEncoderConfigFromParams(encParams, "wristPitch"), | ||
| getEncoderConfigFromParams(armParams, "wristPitch"), | ||
| getMotorConfigFromParams(armParams, "wristPitch"), | ||
| n); | ||
| namedJointPositionMonitors.try_emplace("wristRoll_link", | ||
| "aux2", | ||
| RoboclawChannel::B, | ||
| getEncoderConfigFromParams(encParams, "wristRoll"), | ||
| getEncoderConfigFromParams(armParams, "wristRoll"), | ||
| getMotorConfigFromParams(armParams, "wristRoll"), | ||
| n); |
There was a problem hiding this comment.
SUGGESTION: This may be abstract-able as well.
There was a problem hiding this comment.
Won't do (for now lol)
Pending hardware testing. Do this one before #34