7 const std::vector<FanucGroup> extra_groups)
17 std::vector<FanucAxis> axis;
26 axis.insert(std::end(axis), std::begin(extended_axes), std::end(extended_axes));
32 groups_.insert(std::end(
groups_), std::begin(extra_groups), std::end(extra_groups));
46 return "MovementType not recognized!";
68 throw std::runtime_error(
"Not a valid speed type");
73 std::string configuration(
"");
76 configuration.append(
"F ");
78 configuration.append(
"N ");
81 configuration.append(
"D ");
83 configuration.append(
"U ");
86 configuration.append(
"B");
88 configuration.append(
"T");
98 for (
unsigned i(0); i <
groups_.size(); ++i)
103 for (
unsigned j(0); j <
groups_[i].axis_.size(); ++j)
123 if (
groups_[0].axis_.size() < 6)
129 if (
groups_[0].axis_[0].name_ !=
"X" &&
136 if (
groups_[0].axis_[1].name_ !=
"Y" &&
143 if (
groups_[0].axis_[2].name_ !=
"Z" &&
151 if (
groups_[0].axis_[3].name_ !=
"W" &&
158 if (
groups_[0].axis_[4].name_ !=
"P" &&
164 if (
groups_[0].axis_[5].name_ !=
"R" &&
217 if (group.axis_.empty())
223 if (group.user_frame_ > 9)
229 if (group.tool_frame_ == 0)
235 if (group.tool_frame_ > 9)
249 std::string line(
"");
251 const std::string p_id(std::to_string(
pose_id_));
255 std::string move_speed;
257 move_speed =
"R[" + std::to_string((
unsigned)
speed_) +
"]";
259 move_speed = std::to_string(
unsigned(std::round(speed_)));
261 line = movement +
" P[" + p_id +
"] " + move_speed + speed_unit;
264 line.append(
" FINE");
267 line.append(
" CNT" + std::to_string(
cnt_));
270 line.append(
" ACC" + std::to_string(
acc_));
284 std::string pose_block;
285 pose_block.append(
"P[" + std::to_string(
pose_id_) +
"]{\n");
286 pose_block.append(
" GP1:\n");
288 "\tUF : " + std::to_string(
groups_[0].user_frame_) +
", UT : " 289 + std::to_string(
groups_[0].tool_frame_) +
", CONFIG : '");
292 pose_block.append(
", ");
298 "\tX = " + std::to_string(
groups_[0].axis_[0].value_ * 1000.0) +
" mm, Y = " 299 + std::to_string(
groups_[0].axis_[1].value_ * 1000.0)
300 +
" mm, Z = " + std::to_string(
groups_[0].axis_[2].value_ * 1000.0) +
" mm,\n");
302 "\tW = " + std::to_string(
groups_[0].axis_[3].value_ * 180.0 / M_PI) +
" deg, P = " + std::to_string(
groups_[0].axis_[4].value_* 180.0 / M_PI)
303 +
" deg, R = " + std::to_string(
groups_[0].axis_[5].value_ * 180.0 / M_PI) +
" deg");
306 if (
groups_[0].axis_.size() > 6)
308 pose_block.append(
",\n");
310 for (
unsigned i(6); i <
groups_[0].axis_.size(); ++i)
312 double value(
groups_[0].axis_[i].value_);
314 value *= 180.0 / M_PI;
318 pose_block.append(
"\t");
319 pose_block.append(
groups_[0].axis_[i].name_ +
" = " + std::to_string(value));
322 pose_block.append(
" mm");
324 pose_block.append(
" deg");
326 if (i ==
groups_[0].axis_.size() - 1)
327 pose_block.append(
"\n");
329 pose_block.append(
",\n");
333 pose_block.append(
"\n");
338 for (
unsigned group_number(1); group_number <
groups_.size(); ++group_number)
340 unsigned axis_per_line(0);
342 pose_block.append(
" GP" + std::to_string(group_number + 1) +
":\n");
344 "\tUF : " + std::to_string(
groups_[group_number].user_frame_) +
", UT : " 345 + std::to_string(
groups_[group_number].tool_frame_) +
",\n");
347 for (
auto &axis :
groups_[group_number].axis_)
349 if (axis_per_line == 0)
350 pose_block.append(
"\t");
352 pose_block.append(
" ");
353 pose_block.append(axis.name_ +
"= ");
355 double value(axis.value_);
357 value *= 180.0 / M_PI;
361 pose_block.append(std::to_string(value));
364 pose_block.append(
" mm");
366 pose_block.append(
" deg");
368 if (&axis != &
groups_[group_number].axis_.back())
369 pose_block.append(
",");
371 if (axis_per_line == 2)
373 pose_block.append(
"\n");
380 if (axis_per_line != 0)
381 pose_block.append(
"\n");
386 pose_block.append(
"};\n");
395 Eigen::Vector3d xyz_mm, wpr_deg;
396 industrial_robot_angle_conversions::isometryToFanucPose(pose, xyz_mm, wpr_deg);
398 groups_[0].axis_[0].value_ = xyz_mm.x() / 1e3;
399 groups_[0].axis_[1].value_ = xyz_mm.y() / 1e3;
400 groups_[0].axis_[2].value_ = xyz_mm.z() / 1e3;
402 groups_[0].axis_[3].value_ = wpr_deg[0] * M_PI / 180.0;
403 groups_[0].axis_[4].value_ = wpr_deg[1] * M_PI / 180.0;
404 groups_[0].axis_[5].value_ = wpr_deg[2] * M_PI / 180.0;
std::string configurationToString() const
FanucPose(const std::vector< FanucAxis > extended_axes={}, const std::vector< FanucGroup > extra_groups={})
std::string movementTypeToString() const
std::vector< FanucGroup > groups_
std::string getMainLineString() const
void setRobotPose(const Eigen::Isometry3d &pose)
int flipnonflip_rotations_
bool hasSameGroupsAxes(const FanucPose &other) const
#define ROS_ERROR_STREAM(args)
std::string speedTypeToString() const
std::string getPoseLinesString() const