ros::tf-cascaded-coords
- :super cascaded-coords
- :slots ros::frame-id ros::child-frame-id ros::stamp
:init &rest ros::initargs &key ((:frame-id ros::fid) ) ((:child-frame-id ros::cid) ) ((:stamp ros::st) #i(0 0)) &allow-other-keys
:frame-id &optional id
:child-frame-id &optional id
:stamp &optional ros::st
:prin1 &optional (ros::strm 1)
ros::transformer
- :super ros::object
- :slots ros::cobject
:init
&optional (ros::interpolating t) (ros::cache-time 10.0)
- The Transformer object is the core of tf. It maintains a time-varying graph of transforms, and permits asynchronous graph modification and queries
$ (setq tr (instance ros::transformer :init))
$ (send tr :set-transform (instance ros::tf-cascaded-coords :init :pos #f(1 2 3) :frame-id "this_frame" :child-frame-id "child"))
$ (send tr :get-frame-strings)
("this_frame" "child")
$ (send tr :lookup-transform "this_frame" "child" (ros::time))
$ (send tr :lookup-transform "child" "this_frame" (ros::time))
:all-frames-as-string
- Returns a string representing all frames
:set-transform
coords &optional (ros::auth )
- Adds a new transform to the Transformer graph from euslisp coordinates object
:wait-for-transform
ros::target-frame ros::source-frame ros::time ros::timeout &optional (ros::duration 0.01)
- Waits for the given transformation to become available. If the timeout occurs before the transformation becomes available
:wait-for-transform-full
ros::target-frame ros::target-time ros::source-frame ros::source-time ros::fixed-frame ros::timeout &optional (ros::duration 0.01)
- Extended version of :wait-for-transform
:can-transform
ros::target-frame ros::source-frame ros::time
- Returns True if the Transformer can determine the transform from source_frame to target_frame at time
:can-transform-full
ros::target-frame ros::target-time ros::source-frame ros::source-time ros::fixed-frame
- Extended version of can-transform
:chain
ros::target-frame ros::target-time ros::source-frame ros::source-time ros::fixed-frame
- returns the chain of frames connecting source_frame to target_frame.
:clear
- Clear all transformations.
:frame-exists
ros::frame-id
- returns True if frame frame_id exists in the Transformer.
:get-frame-strings
- returns all frame names in the Transformer as a list
:get-latest-common-time
ros::source-frame ros::target-frame
- Determines the most recent time for which Transformer can compute the transform between the two given frames. Raises tf.Exception if transformation is not possible.
:lookup-transform
ros::target-frame ros::source-frame ros::time
- Returns the transform from source_frame to target_frame at time.
:lookup-transform-full
ros::target-frame ros::target-time ros::source-frame ros::source-time ros::fixed-frame
- Extended version of :lookup-transform
:get-parent
ros::frame_id ros::time
- Fill the parent of a frame.
:set-extrapolation-limit
distance
- Set the distance which tf is allow to extrapolate.
ros::transform-listener
- :super ros::transformer
- :slots nil
:init
&optional (ros::cache-time 10.0) (ros::spin-thread t)
- This class inherits from Transformer and automatically subscribes to ROS transform messages.
:transform-pose
ros::target-frame ros::pose-stamped
- Transform a geometry_msgs::PoseStamped into the target frame
:dispose
ros::transform-broadcaster
- :super ros::object
- :slots ros::cobject
:init
- Construnct transform broadcaster
:send-transform
coords ros::p-frame ros::c-frame &optional ros::tm
- Send a StampedTransform from euslisp coordinates, parent frame, frame_id, and time
ros::buffer-client
- :super ros::object
- :slots ros::cobject
:init
&key (ros::namespace tf2_buffer_server)
(ros::check-frequency 10.0)
(ros::timeout-padding 2.0)
- Construct tf2 buffer object
:wait-for-server
&optional (ros::timeout 5.0)
- Wait for tf2 buffer server
:wait-for-transform
ros::target-frame ros::source-frame ros::rostime ros::timeout &optional (ros::duration 0.05)
- Waits for the given transformation to become available. If the timeout occurs before the transformation becomes available
:can-transform
ros::target-frame ros::source-frame ros::rostime &optional (ros::timeout 0.0)
- Returns t if the Transformer can determine the transform from source_frame to target_frame at time.
:lookup-transform
ros::target-frame ros::source-frame ros::rostime &optional (ros::timeout 0.0)
- Returns the transform from source_frame to target_frame at time.
ros::pos->tf-point
pos
- Convert euslisp pos to geoometry_msgs::Point, this also converts [mm] to [m]
ros::pos->tf-translation
pos
- Convert euslisp pos to geoometry_msgs::Vector3, this also converts [mm] to [m]
ros::rot->tf-quaternion
rot
- Convert euslisp rot to geoometry_msgs::Quaternion
ros::coords->tf-pose
coords
- Convert euslisp coordinates to geoometry_msgs::Pose
ros::coords->tf-pose-stamped
coords id
- Convert euslisp coordinates to geoometry_msgs::PoseStapmed
ros::coords->tf-transform
coords
- Convert euslisp coordinates to geoometry_msgs::Transform
ros::coords->tf-transform-stamped
coords id &optional (ros::child_id )
- Convert euslisp coordinates to geoometry_msgs::TransformStamped
ros::tf-point->pos
ros::point
- Convert geoometry_msgs::Point to euslisp point vector, this aloso converts [m] to [mm]
ros::tf-quaternion->rot
ros::quaternion
- Convert geoometry_msgs::quaternion to euslisp rotation matrix
ros::tf-pose->coords
ros::pose
- Convert geoometry_msgs::Pose to euslisp coordinates
ros::tf-pose-stamped->coords
ros::pose-stamped
- Convert geoometry_msgs::PoseStamped to euslisp coordinates
ros::tf-transform->coords
ros::trans
- Convert geoometry_msgs::Transform to euslisp coordinates
ros::tf-transform-stamped->coords
ros::trans
- Convert geoometry_msgs::TransformStamped to euslisp coordinates
ros::tf-twist->coords
ros::twist
- Convert geoometry_msgs::Twist to euslisp coordinates
ros::create-quaternion-msg-from-rpy
ros::roll ros::pitch ros::yaw
- Create geoometry_msgs::Quaternion from roll, pitch and yaw
ros::identity-quaternion
- Create identity geoemtry_msgs::Quaternion
ros::identity-pose
- Create identity geometry_msgs::Pose
ros::identity-pose-stamped
&optional (ros::header (instance std_msgs::header :init))
- Create identity geometry_msgs::PoseStamped
ros::identity-transform
- Create identity geometry_msgs::Transform
ros::identity-transform-stamped
&optional (ros::header (instance std_msgs::header :init))
- Create identity geometry_msgs::TransformStamped
ros::create-identity-quaternion
ros::create-quaternion-from-rpy ros::roll ros::pitch ros::yaw