geometry_msgs

package
v0.0.0-...-d8760f3 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Sep 17, 2016 License: Apache-2.0 Imports: 5 Imported by: 7

Documentation

Overview

Code generated by ros-gen-go. source: Accel.msg DO NOT EDIT!

Code generated by ros-gen-go. source: AccelStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: AccelWithCovariance.msg DO NOT EDIT!

Code generated by ros-gen-go. source: AccelWithCovarianceStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Inertia.msg DO NOT EDIT!

Code generated by ros-gen-go. source: InertiaStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Point.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Point32.msg DO NOT EDIT!

Code generated by ros-gen-go. source: PointStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Polygon.msg DO NOT EDIT!

Code generated by ros-gen-go. source: PolygonStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Pose.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Pose2D.msg DO NOT EDIT!

Code generated by ros-gen-go. source: PoseArray.msg DO NOT EDIT!

Code generated by ros-gen-go. source: PoseStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: PoseWithCovariance.msg DO NOT EDIT!

Code generated by ros-gen-go. source: PoseWithCovarianceStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Quaternion.msg DO NOT EDIT!

Code generated by ros-gen-go. source: QuaternionStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Transform.msg DO NOT EDIT!

Code generated by ros-gen-go. source: TransformStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Twist.msg DO NOT EDIT!

Code generated by ros-gen-go. source: TwistStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: TwistWithCovariance.msg DO NOT EDIT!

Code generated by ros-gen-go. source: TwistWithCovarianceStamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Vector3.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Vector3Stamped.msg DO NOT EDIT!

Code generated by ros-gen-go. source: Wrench.msg DO NOT EDIT!

Code generated by ros-gen-go. source: WrenchStamped.msg DO NOT EDIT!

Index

Constants

This section is empty.

Variables

View Source
var (
	MsgAccel = &_MsgAccel{
		`# This expresses acceleration in free space broken into its linear and angular parts.
Vector3  linear
Vector3  angular
`,
		"geometry_msgs/Accel",
		"e7128c50122d225a806b2f9ad84736b1",
	}
)
View Source
var (
	MsgAccelStamped = &_MsgAccelStamped{
		`# An accel with reference coordinate frame and timestamp
Header header
Accel accel
`,
		"geometry_msgs/AccelStamped",
		"b50c8c69ae37bb74d3cffd798577ca70",
	}
)
View Source
var (
	MsgAccelWithCovariance = &_MsgAccelWithCovariance{
		`# This expresses acceleration in free space with uncertainty.

Accel accel

# Row-major representation of the 6x6 covariance matrix
# The orientation parameters use a fixed-axis representation.
# In order, the parameters are:
# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
float64[36] covariance
`,
		"geometry_msgs/AccelWithCovariance",
		"c48b3713c98db26549cd6f7fa86d1e4d",
	}
)
View Source
var (
	MsgAccelWithCovarianceStamped = &_MsgAccelWithCovarianceStamped{
		`# This represents an estimated accel with reference coordinate frame and timestamp.
Header header
AccelWithCovariance accel
`,
		"geometry_msgs/AccelWithCovarianceStamped",
		"cf7b852cab243d76000e69f42f2700f6",
	}
)
View Source
var (
	MsgInertia = &_MsgInertia{
		`# Mass [kg]
float64 m

# Center of mass [m]
geometry_msgs/Vector3 com

# Inertia Tensor [kg-m^2]
#     | ixx ixy ixz |
# I = | ixy iyy iyz |
#     | ixz iyz izz |
float64 ixx
float64 ixy
float64 ixz
float64 iyy
float64 iyz
float64 izz
`,
		"geometry_msgs/Inertia",
		"f9eac69d7f8aaf44853616a958d7477f",
	}
)
View Source
var (
	MsgInertiaStamped = &_MsgInertiaStamped{
		`Header header
Inertia inertia
`,
		"geometry_msgs/InertiaStamped",
		"f316819d435fac009022ead4726153cc",
	}
)
View Source
var (
	MsgPoint = &_MsgPoint{
		`# This contains the position of a point in free space
float64 x
float64 y
float64 z
`,
		"geometry_msgs/Point",
		"243a4e5999bbb6bb311c053eea9e3ead",
	}
)
View Source
var (
	MsgPoint32 = &_MsgPoint32{
		`# This contains the position of a point in free space(with 32 bits of precision).
# It is recommeded to use Point wherever possible instead of Point32.  
# 
# This recommendation is to promote interoperability.  
#
# This message is designed to take up less space when sending
# lots of points at once, as in the case of a PointCloud.  

float32 x
float32 y
float32 z`,
		"geometry_msgs/Point32",
		"5513f8375d33dd96e850d3906e193f4a",
	}
)
View Source
var (
	MsgPointStamped = &_MsgPointStamped{
		`# This represents a Point with reference coordinate frame and timestamp
Header header
Point point
`,
		"geometry_msgs/PointStamped",
		"e948b3cf3f45aaeaedb063e8b966cf1f",
	}
)
View Source
var (
	MsgPolygon = &_MsgPolygon{
		`#A specification of a polygon where the first and last points are assumed to be connected
Point32[] points
`,
		"geometry_msgs/Polygon",
		"9d3aa06749458d74b06b6e2ab6c8104d",
	}
)
View Source
var (
	MsgPolygonStamped = &_MsgPolygonStamped{
		`# This represents a Polygon with reference coordinate frame and timestamp
Header header
Polygon polygon
`,
		"geometry_msgs/PolygonStamped",
		"aa0712e581b3057dba582c695ff17d61",
	}
)
View Source
var (
	MsgPose = &_MsgPose{
		`# A representation of pose in free space, composed of postion and orientation. 
Point position
Quaternion orientation
`,
		"geometry_msgs/Pose",
		"dc72bb5c46de72bac142dec5d13c6f57",
	}
)
View Source
var (
	MsgPose2D = &_MsgPose2D{
		`# This expresses a position and orientation on a 2D manifold.

float64 x
float64 y
float64 theta`,
		"geometry_msgs/Pose2D",
		"4e2f3fce2333423b30f6af38b9f2abd7",
	}
)
View Source
var (
	MsgPoseArray = &_MsgPoseArray{
		`# An array of poses with a header for global reference.

Header header

Pose[] poses
`,
		"geometry_msgs/PoseArray",
		"5f3f794301c7af61b3beab5b9997bb64",
	}
)
View Source
var (
	MsgPoseStamped = &_MsgPoseStamped{
		`# A Pose with reference coordinate frame and timestamp
Header header
Pose pose
`,
		"geometry_msgs/PoseStamped",
		"43f3760283d49766c9fdd69c4461f732",
	}
)
View Source
var (
	MsgPoseWithCovariance = &_MsgPoseWithCovariance{
		`# This represents a pose in free space with uncertainty.

Pose pose

# Row-major representation of the 6x6 covariance matrix
# The orientation parameters use a fixed-axis representation.
# In order, the parameters are:
# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
float64[36] covariance
`,
		"geometry_msgs/PoseWithCovariance",
		"4ec31161b30291389f54fb885685270a",
	}
)
View Source
var (
	MsgPoseWithCovarianceStamped = &_MsgPoseWithCovarianceStamped{
		`# This expresses an estimated pose with a reference coordinate frame and timestamp

Header header
PoseWithCovariance pose
`,
		"geometry_msgs/PoseWithCovarianceStamped",
		"729039794eaab042b403222dbf81e197",
	}
)
View Source
var (
	MsgQuaternion = &_MsgQuaternion{
		`# This represents an orientation in free space in quaternion form.

float64 x
float64 y
float64 z
float64 w
`,
		"geometry_msgs/Quaternion",
		"4c29a42d17cc0d0a6ead2e4413ed0e21",
	}
)
View Source
var (
	MsgQuaternionStamped = &_MsgQuaternionStamped{
		`# This represents an orientation with reference coordinate frame and timestamp.

Header header
Quaternion quaternion
`,
		"geometry_msgs/QuaternionStamped",
		"4a5c00199247da86fc3d583bf5af5ca6",
	}
)
View Source
var (
	MsgTransform = &_MsgTransform{
		`# This represents the transform between two coordinate frames in free space.

Vector3 translation
Quaternion rotation
`,
		"geometry_msgs/Transform",
		"756be060b1c8cf0e64a10ba16909d887",
	}
)
View Source
var (
	MsgTransformStamped = &_MsgTransformStamped{
		`# This expresses a transform from coordinate frame header.frame_id
# to the coordinate frame child_frame_id
#
# This message is mostly used by the 
# <a href="http://wiki.ros.org/tf">tf</a> package. 
# See its documentation for more information.

Header header
string child_frame_id # the frame id of the child frame
Transform transform
`,
		"geometry_msgs/TransformStamped",
		"c788bacd82271109656949f89891ee39",
	}
)
View Source
var (
	MsgTwist = &_MsgTwist{
		`# This expresses velocity in free space broken into its linear and angular parts.
Vector3  linear
Vector3  angular
`,
		"geometry_msgs/Twist",
		"7b067cfe31b410bffd4e416af2c10eb0",
	}
)
View Source
var (
	MsgTwistStamped = &_MsgTwistStamped{
		`# A twist with reference coordinate frame and timestamp
Header header
Twist twist
`,
		"geometry_msgs/TwistStamped",
		"08a22ddf566b82f747df9cc6e2fbbf7a",
	}
)
View Source
var (
	MsgTwistWithCovariance = &_MsgTwistWithCovariance{
		`# This expresses velocity in free space with uncertainty.

Twist twist

# Row-major representation of the 6x6 covariance matrix
# The orientation parameters use a fixed-axis representation.
# In order, the parameters are:
# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
float64[36] covariance
`,
		"geometry_msgs/TwistWithCovariance",
		"408e7ef4f4ec295f4663586922faacdd",
	}
)
View Source
var (
	MsgTwistWithCovarianceStamped = &_MsgTwistWithCovarianceStamped{
		`# This represents an estimated twist with reference coordinate frame and timestamp.
Header header
TwistWithCovariance twist
`,
		"geometry_msgs/TwistWithCovarianceStamped",
		"f59b87b044187f26ef66329003c3d275",
	}
)
View Source
var (
	MsgVector3 = &_MsgVector3{
		`# This represents a vector in free space. 
# It is only meant to represent a direction. Therefore, it does not
# make sense to apply a translation to it (e.g., when applying a 
# generic rigid transformation to a Vector3, tf2 will only apply the
# rotation). If you want your data to be translatable too, use the
# geometry_msgs/Point message instead.

float64 x
float64 y
float64 z`,
		"geometry_msgs/Vector3",
		"a661f98e90ac456f3b4330d93aa5ae7e",
	}
)
View Source
var (
	MsgVector3Stamped = &_MsgVector3Stamped{
		`# This represents a Vector3 with reference coordinate frame and timestamp
Header header
Vector3 vector
`,
		"geometry_msgs/Vector3Stamped",
		"25a0f208694a205ef85c426c089ebf78",
	}
)
View Source
var (
	MsgWrench = &_MsgWrench{
		`# This represents force in free space, separated into
# its linear and angular parts.
Vector3  force
Vector3  torque
`,
		"geometry_msgs/Wrench",
		"2aae87faaa553ae28e07e684016d765c",
	}
)
View Source
var (
	MsgWrenchStamped = &_MsgWrenchStamped{
		`# A wrench with reference coordinate frame and timestamp
Header header
Wrench wrench
`,
		"geometry_msgs/WrenchStamped",
		"150502b356390fb151385ef7647f633e",
	}
)

Functions

This section is empty.

Types

type Accel

type Accel struct {
	Linear  Vector3
	Angular Vector3
}

func (*Accel) Deserialize

func (m *Accel) Deserialize(r io.Reader) (err error)

func (*Accel) Serialize

func (m *Accel) Serialize(w io.Writer) (err error)

type AccelStamped

type AccelStamped struct {
	Header std_msgs.Header
	Accel  Accel
}

func (*AccelStamped) Deserialize

func (m *AccelStamped) Deserialize(r io.Reader) (err error)

func (*AccelStamped) Serialize

func (m *AccelStamped) Serialize(w io.Writer) (err error)

type AccelWithCovariance

type AccelWithCovariance struct {
	Accel      Accel
	Covariance [36]float64
}

func (*AccelWithCovariance) Deserialize

func (m *AccelWithCovariance) Deserialize(r io.Reader) (err error)

func (*AccelWithCovariance) Serialize

func (m *AccelWithCovariance) Serialize(w io.Writer) (err error)

type AccelWithCovarianceStamped

type AccelWithCovarianceStamped struct {
	Header std_msgs.Header
	Accel  AccelWithCovariance
}

func (*AccelWithCovarianceStamped) Deserialize

func (m *AccelWithCovarianceStamped) Deserialize(r io.Reader) (err error)

func (*AccelWithCovarianceStamped) Serialize

func (m *AccelWithCovarianceStamped) Serialize(w io.Writer) (err error)

type Inertia

type Inertia struct {
	M   float64
	Com Vector3
	Ixx float64
	Ixy float64
	Ixz float64
	Iyy float64
	Iyz float64
	Izz float64
}

func (*Inertia) Deserialize

func (m *Inertia) Deserialize(r io.Reader) (err error)

func (*Inertia) Serialize

func (m *Inertia) Serialize(w io.Writer) (err error)

type InertiaStamped

type InertiaStamped struct {
	Header  std_msgs.Header
	Inertia Inertia
}

func (*InertiaStamped) Deserialize

func (m *InertiaStamped) Deserialize(r io.Reader) (err error)

func (*InertiaStamped) Serialize

func (m *InertiaStamped) Serialize(w io.Writer) (err error)

type Point

type Point struct {
	X float64
	Y float64
	Z float64
}

func (*Point) Deserialize

func (m *Point) Deserialize(r io.Reader) (err error)

func (*Point) Serialize

func (m *Point) Serialize(w io.Writer) (err error)

type Point32

type Point32 struct {
	X float32
	Y float32
	Z float32
}

func (*Point32) Deserialize

func (m *Point32) Deserialize(r io.Reader) (err error)

func (*Point32) Serialize

func (m *Point32) Serialize(w io.Writer) (err error)

type PointStamped

type PointStamped struct {
	Header std_msgs.Header
	Point  Point
}

func (*PointStamped) Deserialize

func (m *PointStamped) Deserialize(r io.Reader) (err error)

func (*PointStamped) Serialize

func (m *PointStamped) Serialize(w io.Writer) (err error)

type Polygon

type Polygon struct {
	Points []Point32
}

func (*Polygon) Deserialize

func (m *Polygon) Deserialize(r io.Reader) (err error)

func (*Polygon) Serialize

func (m *Polygon) Serialize(w io.Writer) (err error)

type PolygonStamped

type PolygonStamped struct {
	Header  std_msgs.Header
	Polygon Polygon
}

func (*PolygonStamped) Deserialize

func (m *PolygonStamped) Deserialize(r io.Reader) (err error)

func (*PolygonStamped) Serialize

func (m *PolygonStamped) Serialize(w io.Writer) (err error)

type Pose

type Pose struct {
	Position    Point
	Orientation Quaternion
}

func (*Pose) Deserialize

func (m *Pose) Deserialize(r io.Reader) (err error)

func (*Pose) Serialize

func (m *Pose) Serialize(w io.Writer) (err error)

type Pose2D

type Pose2D struct {
	X     float64
	Y     float64
	Theta float64
}

func (*Pose2D) Deserialize

func (m *Pose2D) Deserialize(r io.Reader) (err error)

func (*Pose2D) Serialize

func (m *Pose2D) Serialize(w io.Writer) (err error)

type PoseArray

type PoseArray struct {
	Header std_msgs.Header
	Poses  []Pose
}

func (*PoseArray) Deserialize

func (m *PoseArray) Deserialize(r io.Reader) (err error)

func (*PoseArray) Serialize

func (m *PoseArray) Serialize(w io.Writer) (err error)

type PoseStamped

type PoseStamped struct {
	Header std_msgs.Header
	Pose   Pose
}

func (*PoseStamped) Deserialize

func (m *PoseStamped) Deserialize(r io.Reader) (err error)

func (*PoseStamped) Serialize

func (m *PoseStamped) Serialize(w io.Writer) (err error)

type PoseWithCovariance

type PoseWithCovariance struct {
	Pose       Pose
	Covariance [36]float64
}

func (*PoseWithCovariance) Deserialize

func (m *PoseWithCovariance) Deserialize(r io.Reader) (err error)

func (*PoseWithCovariance) Serialize

func (m *PoseWithCovariance) Serialize(w io.Writer) (err error)

type PoseWithCovarianceStamped

type PoseWithCovarianceStamped struct {
	Header std_msgs.Header
	Pose   PoseWithCovariance
}

func (*PoseWithCovarianceStamped) Deserialize

func (m *PoseWithCovarianceStamped) Deserialize(r io.Reader) (err error)

func (*PoseWithCovarianceStamped) Serialize

func (m *PoseWithCovarianceStamped) Serialize(w io.Writer) (err error)

type Quaternion

type Quaternion struct {
	X float64
	Y float64
	Z float64
	W float64
}

func (*Quaternion) Deserialize

func (m *Quaternion) Deserialize(r io.Reader) (err error)

func (*Quaternion) Serialize

func (m *Quaternion) Serialize(w io.Writer) (err error)

type QuaternionStamped

type QuaternionStamped struct {
	Header     std_msgs.Header
	Quaternion Quaternion
}

func (*QuaternionStamped) Deserialize

func (m *QuaternionStamped) Deserialize(r io.Reader) (err error)

func (*QuaternionStamped) Serialize

func (m *QuaternionStamped) Serialize(w io.Writer) (err error)

type Transform

type Transform struct {
	Translation Vector3
	Rotation    Quaternion
}

func (*Transform) Deserialize

func (m *Transform) Deserialize(r io.Reader) (err error)

func (*Transform) Serialize

func (m *Transform) Serialize(w io.Writer) (err error)

type TransformStamped

type TransformStamped struct {
	Header       std_msgs.Header
	ChildFrameID string
	Transform    Transform
}

func (*TransformStamped) Deserialize

func (m *TransformStamped) Deserialize(r io.Reader) (err error)

func (*TransformStamped) Serialize

func (m *TransformStamped) Serialize(w io.Writer) (err error)

type Twist

type Twist struct {
	Linear  Vector3
	Angular Vector3
}

func (*Twist) Deserialize

func (m *Twist) Deserialize(r io.Reader) (err error)

func (*Twist) Serialize

func (m *Twist) Serialize(w io.Writer) (err error)

type TwistStamped

type TwistStamped struct {
	Header std_msgs.Header
	Twist  Twist
}

func (*TwistStamped) Deserialize

func (m *TwistStamped) Deserialize(r io.Reader) (err error)

func (*TwistStamped) Serialize

func (m *TwistStamped) Serialize(w io.Writer) (err error)

type TwistWithCovariance

type TwistWithCovariance struct {
	Twist      Twist
	Covariance [36]float64
}

func (*TwistWithCovariance) Deserialize

func (m *TwistWithCovariance) Deserialize(r io.Reader) (err error)

func (*TwistWithCovariance) Serialize

func (m *TwistWithCovariance) Serialize(w io.Writer) (err error)

type TwistWithCovarianceStamped

type TwistWithCovarianceStamped struct {
	Header std_msgs.Header
	Twist  TwistWithCovariance
}

func (*TwistWithCovarianceStamped) Deserialize

func (m *TwistWithCovarianceStamped) Deserialize(r io.Reader) (err error)

func (*TwistWithCovarianceStamped) Serialize

func (m *TwistWithCovarianceStamped) Serialize(w io.Writer) (err error)

type Vector3

type Vector3 struct {
	X float64
	Y float64
	Z float64
}

func (*Vector3) Deserialize

func (m *Vector3) Deserialize(r io.Reader) (err error)

func (*Vector3) Serialize

func (m *Vector3) Serialize(w io.Writer) (err error)

type Vector3Stamped

type Vector3Stamped struct {
	Header std_msgs.Header
	Vector Vector3
}

func (*Vector3Stamped) Deserialize

func (m *Vector3Stamped) Deserialize(r io.Reader) (err error)

func (*Vector3Stamped) Serialize

func (m *Vector3Stamped) Serialize(w io.Writer) (err error)

type Wrench

type Wrench struct {
	Force  Vector3
	Torque Vector3
}

func (*Wrench) Deserialize

func (m *Wrench) Deserialize(r io.Reader) (err error)

func (*Wrench) Serialize

func (m *Wrench) Serialize(w io.Writer) (err error)

type WrenchStamped

type WrenchStamped struct {
	Header std_msgs.Header
	Wrench Wrench
}

func (*WrenchStamped) Deserialize

func (m *WrenchStamped) Deserialize(r io.Reader) (err error)

func (*WrenchStamped) Serialize

func (m *WrenchStamped) Serialize(w io.Writer) (err error)

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL