2 #include <rokubimini_msgs/Reading.h>
6 #include <diagnostic_msgs/DiagnosticArray.h>
53 return slavePtr_->getSerialNumber(serialNumber);
58 return slavePtr_->getForceTorqueSamplingRate(samplingRate);
63 return slavePtr_->setForceTorqueFilter(filter);
68 return slavePtr_->setAccelerationFilter(filter);
73 return slavePtr_->setAngularRateFilter(filter);
78 return slavePtr_->setAccelerationRange(range);
83 return slavePtr_->setAngularRateRange(range);
88 return slavePtr_->setForceTorqueOffset(forceTorqueOffset);
93 if (!
slavePtr_->setSensorConfiguration(sensorConfiguration))
103 if (!
slavePtr_->setSensorCalibration(sensorCalibration))
133 nh_->getNamespace() +
"/" +
getName() +
"/ft_sensor_readings/reading", 10,
false));
136 nh_->getNamespace() +
"/" +
getName() +
"/ft_sensor_readings/wrench", 10,
false));
142 nh_->getNamespace() +
"/" +
getName() +
"/ft_sensor_readings/temperature", 10,
false));
144 std::make_shared<ros::Publisher>(
nh_->advertise<diagnostic_msgs::DiagnosticArray>(
"/diagnostics", 10,
false));
154 rokubimini_msgs::Reading reading_msg;
155 reading_msg.header.stamp = reading.getWrench().header.stamp;
157 reading_msg.statusword = reading.getStatusword().getData();
158 reading_msg.imu = reading.getImu();
159 reading_msg.wrench = reading.getWrench();
160 reading_msg.externalImu = reading.getExternalImu();
161 reading_msg.isForceTorqueSaturated = reading.isForceTorqueSaturated();
162 reading_msg.temperature = reading.getTemperature();
191 std::this_thread::sleep_for(std::chrono::microseconds(500));
192 kill(getpid(), SIGINT);
203 unsigned int serial_number;
226 slavePtr_->createDataFlagsDiagnostics(stat);
230 stat.name =
nh_->getNamespace().substr(1) +
": " +
getName() +
": Data Flags";
232 unsigned int serial_number;
234 stat.hardware_id = std::to_string(serial_number);
236 diagnostic_msgs::DiagnosticArray diagnostics_array;
237 diagnostics_array.status.emplace_back(stat);
244 rokubimini_msgs::FirmwareUpdateEthercat::Response& response)
246 response.result =
slavePtr_->firmwareUpdate(request.file_path, request.file_name, request.password);
251 shutdown_thread.detach();
257 rokubimini_msgs::ResetWrench::Response& response)
259 ROS_INFO(
"[%s] Reseting sensor measurements...",
name_.c_str());
261 bool success =
false;
262 unsigned int count = 0;
263 Eigen::Matrix<double, 6, 1> new_offset;
265 while (!success and count < 8)
278 ROS_ERROR(
"[%s] Device could not switch to config mode",
name_.c_str());
282 geometry_msgs::Wrench wrench;
283 Eigen::Matrix<double, 6, 1> mean_wrench;
288 wrench.force.x = mean_wrench(0, 0);
289 wrench.force.y = mean_wrench(1, 0);
290 wrench.force.z = mean_wrench(2, 0);
291 wrench.torque.x = mean_wrench(3, 0);
292 wrench.torque.y = mean_wrench(4, 0);
293 wrench.torque.z = mean_wrench(5, 0);
295 geometry_msgs::Wrench desired_wrench = request.desired_wrench;
298 new_offset(0, 0) = desired_wrench.force.x - wrench.force.x + current_offset(0, 0);
299 new_offset(1, 0) = desired_wrench.force.y - wrench.force.y + current_offset(1, 0);
300 new_offset(2, 0) = desired_wrench.force.z - wrench.force.z + current_offset(2, 0);
301 new_offset(3, 0) = desired_wrench.torque.x - wrench.torque.x + current_offset(3, 0);
302 new_offset(4, 0) = desired_wrench.torque.y - wrench.torque.y + current_offset(4, 0);
303 new_offset(5, 0) = desired_wrench.torque.z - wrench.torque.z + current_offset(5, 0);
305 <<
"New offset is: " << new_offset);
308 ROS_ERROR(
"[%s] Could not write new offset to device",
name_.c_str());
314 ROS_ERROR(
"[%s] Device could not switch to run mode",
name_.c_str());
336 Eigen::Vector3d forceError;
337 forceError << mean_wrench(0, 0) - desired_wrench.force.x, mean_wrench(1, 0) - desired_wrench.force.y,
338 mean_wrench(2, 0) - desired_wrench.force.z;
339 if (forceError.norm() > 0.2)
345 Eigen::Vector3d torqueError;
346 torqueError << mean_wrench(3, 0) - desired_wrench.torque.x, mean_wrench(4, 0) - desired_wrench.torque.y,
347 mean_wrench(5, 0) - desired_wrench.torque.z;
348 if (torqueError.norm() > 0.01)
357 ROS_INFO(
"[%s] Sensor measurements are reset successfully",
name_.c_str());
368 const std::string& valueTypeString, std::string& valueString)
370 return slavePtr_->sendSdoReadGeneric(indexString, subindexString, valueTypeString, valueString);
374 const std::string& valueTypeString,
const std::string& valueString)
376 return slavePtr_->sendSdoWriteGeneric(indexString, subindexString, valueTypeString, valueString);
383 return slavePtr_->sendSdoReadInt8(index, subindex, completeAccess, value);
390 return slavePtr_->sendSdoReadInt16(index, subindex, completeAccess, value);
397 return slavePtr_->sendSdoReadInt32(index, subindex, completeAccess, value);
404 return slavePtr_->sendSdoReadInt64(index, subindex, completeAccess, value);
411 return slavePtr_->sendSdoReadUInt8(index, subindex, completeAccess, value);
418 return slavePtr_->sendSdoReadUInt16(index, subindex, completeAccess, value);
425 return slavePtr_->sendSdoReadUInt32(index, subindex, completeAccess, value);
432 return slavePtr_->sendSdoReadUInt64(index, subindex, completeAccess, value);
439 return slavePtr_->sendSdoReadFloat(index, subindex, completeAccess, value);
446 return slavePtr_->sendSdoReadDouble(index, subindex, completeAccess, value);
453 return slavePtr_->sendSdoWriteInt8(index, subindex, completeAccess, value);
460 return slavePtr_->sendSdoWriteInt16(index, subindex, completeAccess, value);
467 return slavePtr_->sendSdoWriteInt32(index, subindex, completeAccess, value);
474 return slavePtr_->sendSdoWriteInt64(index, subindex, completeAccess, value);
481 return slavePtr_->sendSdoWriteUInt8(index, subindex, completeAccess, value);
488 return slavePtr_->sendSdoWriteUInt16(index, subindex, completeAccess, value);
495 return slavePtr_->sendSdoWriteUInt32(index, subindex, completeAccess, value);
502 return slavePtr_->sendSdoWriteUInt64(index, subindex, completeAccess, value);
509 return slavePtr_->sendSdoWriteFloat(index, subindex, completeAccess, value);
516 return slavePtr_->sendSdoWriteDouble(index, subindex, completeAccess, value);