30 const std::string& frame_id)
32 poses_stamped.clear();
34 if (time_series.
isEmpty())
return;
38 poses_stamped.emplace_back();
43 poses_stamped.back().header.frame_id = frame_id;
void convert(const corbo::TimeSeries &time_series, const RobotDynamicsInterface &dynamics, std::vector< geometry_msgs::PoseStamped > &poses_stamped, const std::string &frame_id)
Convert TimeSeries to pose array.
int getTimeDimension() const
virtual void getPoseSE2FromState(const Eigen::Ref< const Eigen::VectorXd > &x, double &pos_x, double &pos_y, double &theta) const =0
Convert state vector to pose (x,y,theta)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
Eigen::Map< const Eigen::VectorXd > getValuesMap(int time_idx) const
Specialization of SystemDynamicsInterface for mobile robots.