Skip to content

Commit 8ca56ef

Browse files
authored
Merge pull request #10 from SchillingRobotics/bijoua/handle_meas_state_nan
Handle NaNs in measured state in CTG
2 parents 92e7139 + 6b118f4 commit 8ca56ef

File tree

1 file changed

+35
-10
lines changed

1 file changed

+35
-10
lines changed

joint_trajectory_controller/src/cartesian_trajectory_generator.cpp

Lines changed: 35 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -385,34 +385,59 @@ bool CartesianTrajectoryGenerator::read_state_from_hardware(JointTrajectoryPoint
385385
std::array<double, 3> orientation_angles;
386386
const auto measured_state = *(feedback_.readFromRT());
387387
if (!measured_state) return false;
388+
388389
tf2::Quaternion measured_q;
389-
tf2::fromMsg(measured_state->pose.pose.orientation, measured_q);
390+
391+
if (
392+
std::isnan(measured_state->pose.pose.orientation.w) ||
393+
std::isnan(measured_state->pose.pose.orientation.x) ||
394+
std::isnan(measured_state->pose.pose.orientation.y) ||
395+
std::isnan(measured_state->pose.pose.orientation.z))
396+
{
397+
// if any of the orientation is NaN, revert to previous orientation
398+
measured_q.setRPY(state.positions[3], state.positions[4], state.positions[5]);
399+
}
400+
else
401+
{
402+
tf2::fromMsg(measured_state->pose.pose.orientation, measured_q);
403+
}
390404
tf2::Matrix3x3 m(measured_q);
391405
m.getRPY(orientation_angles[0], orientation_angles[1], orientation_angles[2]);
392406

393407
// Assign values from the hardware
394408
// Position states always exist
395-
state.positions[0] = measured_state->pose.pose.position.x;
396-
state.positions[1] = measured_state->pose.pose.position.y;
397-
state.positions[2] = measured_state->pose.pose.position.z;
409+
// if any measured position is NaN, keep previous value
410+
state.positions[0] = std::isnan(measured_state->pose.pose.position.x)
411+
? state.positions[0]
412+
: measured_state->pose.pose.position.x;
413+
state.positions[1] = std::isnan(measured_state->pose.pose.position.y)
414+
? state.positions[1]
415+
: measured_state->pose.pose.position.y;
416+
state.positions[2] = std::isnan(measured_state->pose.pose.position.z)
417+
? state.positions[2]
418+
: measured_state->pose.pose.position.z;
398419
state.positions[3] = orientation_angles[0];
399420
state.positions[4] = orientation_angles[1];
400421
state.positions[5] = orientation_angles[2];
401422

402423
////// Convert measured twist which is in body frame to world frame since CTG/JTC expects state in world frame
403424

404425
Eigen::Quaterniond q_body_in_world(
405-
measured_state->pose.pose.orientation.w, measured_state->pose.pose.orientation.x,
406-
measured_state->pose.pose.orientation.y, measured_state->pose.pose.orientation.z);
426+
measured_q.w(), measured_q.x(), measured_q.y(), measured_q.z());
407427

428+
// if any measured linear velocity is NaN, set to zero
408429
Eigen::Vector3d linear_vel_body(
409-
measured_state->twist.twist.linear.x, measured_state->twist.twist.linear.y,
410-
measured_state->twist.twist.linear.z);
430+
std::isnan(measured_state->twist.twist.linear.x) ? 0.0 : measured_state->twist.twist.linear.x,
431+
std::isnan(measured_state->twist.twist.linear.y) ? 0.0 : measured_state->twist.twist.linear.y,
432+
std::isnan(measured_state->twist.twist.linear.z) ? 0.0 : measured_state->twist.twist.linear.z);
411433
auto linear_vel_world = q_body_in_world * linear_vel_body;
412434

435+
// if any measured angular velocity is NaN, set to zero
413436
Eigen::Vector3d angular_vel_body(
414-
measured_state->twist.twist.angular.x, measured_state->twist.twist.angular.y,
415-
measured_state->twist.twist.angular.z);
437+
std::isnan(measured_state->twist.twist.angular.x) ? 0.0 : measured_state->twist.twist.angular.x,
438+
std::isnan(measured_state->twist.twist.angular.y) ? 0.0 : measured_state->twist.twist.angular.y,
439+
std::isnan(measured_state->twist.twist.angular.z) ? 0.0
440+
: measured_state->twist.twist.angular.z);
416441
auto angular_vel_world = q_body_in_world * angular_vel_body;
417442

418443
state.velocities[0] = linear_vel_world[0];

0 commit comments

Comments
 (0)