Skip to content

Conversation

@alireza-moayyedi
Copy link
Contributor

Currently there are conversions available between Eigen and Twist but not Accel. With this PR, I wanted to add the same type of conversion for Accel as well.

I have added fromMSg but I also wish to add toMsg for Accel. However, since Eigen just uses a 6x1 matrix, there would be no distinction between a Twist Eigen matrix and an Acceleration Eigen matrix. Hence the toMsg for Accel would then have the same input as the Eigen to Twist toMsg and it would throw ambiguity error:

geometry_msgs::msg::Twist toMsg(const Eigen::Matrix<double, 6, 1> & in)
{
  geometry_msgs::msg::Twist msg;
  msg.linear.x = in[0];
  msg.linear.y = in[1];
  msg.linear.z = in[2];
  msg.angular.x = in[3];
  msg.angular.y = in[4];
  msg.angular.z = in[5];
  return msg;
}

geometry_msgs::msg::Accel toMsg(const Eigen::Matrix<double, 6, 1> & in)
{
  geometry_msgs::msg::Accel msg;
  msg.linear.x = in[0];
  msg.linear.y = in[1];
  msg.linear.z = in[2];
  msg.angular.x = in[3];
  msg.angular.y = in[4];
  msg.angular.z = in[5];
  return msg;
}

A workaround for this would be to also pass the output as reference for acceleration's toMsg hence keeping the api the same for Twist's toMsg while introducing a new one for Accel but that would be against the current design pattern for toMsg functions. Curious to know what you think:

void toMsg(const Eigen::Matrix<double, 6, 1> & in, geometry_msgs::msg::Accel& out )
{
  out.linear.x = in[0];
  out.linear.y = in[1];
  out.linear.z = in[2];
  out.angular.x = in[3];
  out.angular.y = in[4];
  out.angular.z = in[5];
}

If you think it is okay to allow such toMsg implementation for Eigen to Accel then I will extend the PR.

@alireza-moayyedi
Copy link
Contributor Author

I just noticed that the workaround is actually already implemented for Vector3 and Point which have the same issue as described above:

geometry_msgs::msg::Point toMsg(const Eigen::Vector3d & in)
geometry_msgs::msg::Vector3 & toMsg(const Eigen::Vector3d & in, geometry_msgs::msg::Vector3 & out)

I guess then it's fine to proceed with what I suggested for Accel's toMsg?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant