Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
6 changes: 3 additions & 3 deletions blue_bringup/config/robot_parameters_left.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@ blue_hardware:
joint_torque_directions: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
id_torque_gains: [1.12, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
softstop_min_angles: [-2.2, -2.25, -2.6, -2.25, -2.6, -2.25, -2.6, -1.45]
softstop_max_angles: [3.3, 0.5, 2.6, .5, 2.6, 0.5, 2.6, 1.45]
softstop_tolerance: 0.19
softstop_torque_limit: 95.0
softstop_max_angles: [ 2.8, 0.1, 2.6, 0.1, 2.6, 0.1, 2.6, 1.45]
softstop_tolerance: 0.2
softstop_torque_gains: [65, 20, 20, 10, 10, 4, 4, 0]

### Motor configuration
motor_names:
Expand Down
4 changes: 2 additions & 2 deletions blue_bringup/config/robot_parameters_right.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@ blue_hardware:
joint_torque_directions: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
id_torque_gains: [1.12, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
softstop_min_angles: [-3.3, -2.25, -2.6, -2.25, -2.6, -2.25, -2.6, -1.45]
softstop_max_angles: [2.2, 0.5, 2.6, 0.5, 2.6, 0.2, 2.6, 1.45]
softstop_max_angles: [ 2.2, 0.5, 2.6, 0.5, 2.6, 0.2, 2.6, 1.45]
softstop_tolerance: 0.19
softstop_torque_limit: 95.0
softstop_torque_gains: [65, 20, 20, 10, 10, 4, 4, 0]

### Motor configuration
motor_names:
Expand Down
2 changes: 1 addition & 1 deletion blue_descriptions/urdf/gripper_v1/gripper.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@
type="revolute">
<origin
xyz="0 0 -0.10"
rpy="1.5 1.5 0" />
rpy="-1.5708 -2.4803E-15 -3.1416" />
<parent
link="${side}_${parent}" />
<child
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ typedef struct {

// Soft stops
// TODO: hacky and temporary
double softstop_torque_limit;
std::vector<double> softstop_torque_gains;
std::vector<double> softstop_min_angles;
std::vector<double> softstop_max_angles;
double softstop_tolerance;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class BlueKinematics
// Get desired actuator commands
std::vector<double> getActuatorCommands(
const std::vector<double> &feedforward_torques,
double softstop_torque_limit, // TODO: clean up softstop code
const std::vector<double> &softstop_torque_gains,
const std::vector<double> &softstop_min_angles,
const std::vector<double> &softstop_max_angles,
double softstop_tolerance);
Expand Down
4 changes: 2 additions & 2 deletions blue_hardware_interface/src/blue_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ void BlueHW::write() {
// Get actuator commands, using the gravity comp torques as a feedforward
auto actuator_commands = kinematics_.getActuatorCommands(
feedforward_torques,
params_.softstop_torque_limit, // TODO: clean up softstop code
params_.softstop_torque_gains, // TODO: clean up softstop code
params_.softstop_min_angles,
params_.softstop_max_angles,
params_.softstop_tolerance);
Expand Down Expand Up @@ -178,7 +178,7 @@ void BlueHW::loadParams() {

// Soft stops
// TODO: hacky and temporary
getParam("blue_hardware/softstop_torque_limit", params_.softstop_torque_limit);
getParam("blue_hardware/softstop_torque_gains", params_.softstop_torque_gains);
getParam("blue_hardware/softstop_min_angles", params_.softstop_min_angles);
getParam("blue_hardware/softstop_max_angles", params_.softstop_max_angles);
getParam("blue_hardware/softstop_tolerance", params_.softstop_tolerance);
Expand Down
46 changes: 33 additions & 13 deletions blue_hardware_interface/src/blue_kinematics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -369,7 +369,7 @@ void BlueKinematics::getGravityVectors(

std::vector<double> BlueKinematics::getActuatorCommands(
const std::vector<double> &feedforward_torques,
double softstop_torque_limit, // TODO: clean up softstop code
const std::vector<double> &softstop_torque_gains,
const std::vector<double> &softstop_min_angles,
const std::vector<double> &softstop_max_angles,
double softstop_tolerance) {
Expand All @@ -385,23 +385,43 @@ std::vector<double> BlueKinematics::getActuatorCommands(

// Compute joint commands
for (int i = 0; i < num_joints_; i++) {
// Add feedforward if it exists
if (i < feedforward_torques.size())
joint_cmd_[i] = raw_joint_cmd_[i] + feedforward_torques[i];
else
joint_cmd_[i] = raw_joint_cmd_[i];

joint_cmd_[i] = raw_joint_cmd_[i];
raw_joint_cmd_[i] = 0.0;

// Soft stops
// TODO: hacky and temporary
if(joint_pos_[i] > softstop_max_angles[i] - softstop_tolerance) {
double offset = joint_pos_[i] - softstop_max_angles[i] + softstop_tolerance;
joint_cmd_[i] += -1.0 * softstop_torque_limit * pow(offset, 2);
} else if (joint_pos_[i] < softstop_min_angles[i] + softstop_tolerance) {
double offset = softstop_min_angles[i] + softstop_tolerance - joint_pos_[i];
joint_cmd_[i] += softstop_torque_limit * pow(offset, 2);
double eps_vel = 0.1;
if(joint_pos_[i] > (softstop_max_angles[i] - softstop_tolerance) && joint_vel_[i] > 0) {
double offset = joint_pos_[i] - (softstop_max_angles[i] - softstop_tolerance);
double spring = offset * softstop_torque_gains[i];
double applied = std::min(spring, joint_vel_[i]);
joint_cmd_[i] += -applied;

// if(joint_pos_[i] > softstop_max_angles[i] - softstop_tolerance/2.0) {
// joint_cmd_[i] += -0.5 * softstop_torque_gains[i] * joint_vel_[i];
// } else if (joint_vel_[i] < 0) {
// joint_cmd_[i] += -1.0 * offset * softstop_torque_gains[i] * joint_vel_[i];
// }
// joint_cmd_[i] += -0.2 * softstop_torque_gains[i] * pow(offset, 1);
// joint_cmd_[i] += -0.5 * softstop_torque_gains[i] * joint_vel_[i];

} else if (joint_pos_[i] < (softstop_min_angles[i] + softstop_tolerance) && joint_vel_[i] < 0) {
double offset = (softstop_min_angles[i] + softstop_tolerance) - joint_pos_[i];
double spring = offset * softstop_torque_gains[i];
double applied = std::min(spring, -joint_vel_[i]);
joint_cmd_[i] += applied;
// if(joint_pos_[i] < softstop_min_angles[i] + softstop_tolerance/2.0) {
// joint_cmd_[i] += -0.5 * softstop_torque_gains[i] * joint_vel_[i];
// } else if (joint_vel_[i] > 0) {
// joint_cmd_[i] += -1.0 *offset *softstop_torque_gains[i] * joint_vel_[i];
// }
// joint_cmd_[i] += 0.2 * softstop_torque_gains[i] * pow(offset, 1);
// joint_cmd_[i] += -0.5 * softstop_torque_gains[i] * joint_vel_[i];
}

// Add feedforward if it exists
if (i < feedforward_torques.size())
joint_cmd_[i] = joint_cmd_[i] + feedforward_torques[i];
}

// Propagate through transmissions to compute actuator commands
Expand Down