20 #pragma clang diagnostic push
21 #pragma clang diagnostic ignored "-Wimplicit-conversion"
23 #pragma clang diagnostic pop
43 return {transform * pose_, transform * velocity_};
Definition: cartesian_state.hpp:17
CartesianState(const RobotPose &pose, const RobotVelocity &velocity)
Definition: cartesian_state.hpp:29
RobotPose pose() const
Definition: cartesian_state.hpp:60
CartesianState(const RobotPose &pose)
Definition: cartesian_state.hpp:22
CartesianState changeEndEffectorFrame(const Affine &transform) const
Change the end effector frame of the state by the given affine transform.
Definition: cartesian_state.hpp:52
CartesianState transformWith(const Affine &transform) const
Transform the frame of the state by applying the given affine transform.
Definition: cartesian_state.hpp:42
CartesianState(const CartesianState &)=default
RobotVelocity velocity() const
Definition: cartesian_state.hpp:67
Cartesian pose of a robot.
Definition: robot_pose.hpp:16
RobotPose changeEndEffectorFrame(const Affine &transform) const
Change the frame of the end effector by applying a transformation from the right side....
Definition: robot_pose.hpp:91
Affine end_effector_pose() const
Get the end effector pose.
Definition: robot_pose.hpp:110
Cartesian velocity of a robot.
Definition: robot_velocity.hpp:18
RobotVelocity changeEndEffectorFrame(const Eigen::Vector3d &offset_world_frame) const
Change the end-effector frame by adding the given offset to the current end-effector frame....
Definition: robot_velocity.hpp:87
Definition: gripper.cpp:3
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition: cartesian_state.hpp:76
Eigen::Affine3d Affine
Definition: types.hpp:13