22#ifndef YARP_ROSMSG_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
23#define YARP_ROSMSG_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
41 std::vector<yarp::rosmsg::geometry_msgs::Transform>
transforms;
42 std::vector<yarp::rosmsg::geometry_msgs::Twist>
velocities;
74 for (
int i=0; i<len; i++) {
83 for (
int i=0; i<len; i++) {
92 for (
int i=0; i<len; i++) {
120 for (
int i=0; i<len; i++) {
132 for (
int i=0; i<len; i++) {
144 for (
int i=0; i<len; i++) {
253 static constexpr const char*
typeName =
"trajectory_msgs/MultiDOFJointTrajectoryPoint";
256 static constexpr const char*
typeChecksum =
"3ebe08d1abd5b65862d50e09430db776";
260# Each multi-dof joint can specify a transform (up to 6 DOF)\n\
261geometry_msgs/Transform[] transforms\n\
263# There can be a velocity specified for the origin of the joint \n\
264geometry_msgs/Twist[] velocities\n\
266# There can be an acceleration specified for the origin of the joint \n\
267geometry_msgs/Twist[] accelerations\n\
269duration time_from_start\n\
271================================================================================\n\
272MSG: geometry_msgs/Transform\n\
273# This represents the transform between two coordinate frames in free space.\n\
275Vector3 translation\n\
276Quaternion rotation\n\
278================================================================================\n\
279MSG: geometry_msgs/Vector3\n\
280# This represents a vector in free space. \n\
281# It is only meant to represent a direction. Therefore, it does not\n\
282# make sense to apply a translation to it (e.g., when applying a \n\
283# generic rigid transformation to a Vector3, tf2 will only apply the\n\
284# rotation). If you want your data to be translatable too, use the\n\
285# geometry_msgs/Point message instead.\n\
290================================================================================\n\
291MSG: geometry_msgs/Quaternion\n\
292# This represents an orientation in free space in quaternion form.\n\
299================================================================================\n\
300MSG: geometry_msgs/Twist\n\
301# This expresses velocity in free space broken into its linear and angular parts.\n\
An interface for reading from a network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
virtual bool isError() const =0
An interface for writing to a network connection.
virtual bool isError() const =0
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
static Type byName(const char *name)
Type & addProperty(const char *key, const Value &val)
A single value (typically within a Bottle).
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::rosmsg::TickDuration time_from_start
std::vector< yarp::rosmsg::geometry_msgs::Twist > velocities
std::vector< yarp::rosmsg::geometry_msgs::Transform > transforms
static constexpr const char * typeChecksum
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
static constexpr const char * typeText
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
yarp::os::idl::BottleStyle< yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint > bottleStyle
bool readBottle(yarp::os::ConnectionReader &connection) override
bool writeBare(yarp::os::ConnectionWriter &connection) const override
std::vector< yarp::rosmsg::geometry_msgs::Twist > accelerations
static constexpr const char * typeName
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::os::Type getType() const override
MultiDOFJointTrajectoryPoint()
yarp::os::idl::BareStyle< yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint > rosStyle
The main, catch-all namespace for YARP.