40  virtual std::pair<RobotState, Duration> 
readOnce() = 0;
 
   57                         const std::optional<const Torques>& ) = 0;
 
   66                         const std::optional<const Torques>& ) = 0;
 
   74                         const std::optional<const Torques>& ) = 0;
 
   83                         const std::optional<const Torques>& ) = 0;
 
 
Allows the user to read the state of a Robot and to send new control commands after starting a contro...
Definition active_control_base.h:27
 
virtual void writeOnce(const Torques &)=0
Updates torque commands of an active control.
 
virtual void writeOnce(const CartesianVelocities &motion_generator_input)=0
Updates the cartesian velocity commands of an active control, with internal controller.
 
virtual void writeOnce(const JointVelocities &, const std::optional< const Torques > &)=0
Updates the joint velocity and torque commands of an active control.
 
virtual void writeOnce(const CartesianPose &, const std::optional< const Torques > &)=0
Updates the cartesian position and torque commands of an active control.
 
virtual std::pair< RobotState, Duration > readOnce()=0
Waits for a robot state update and returns it.
 
virtual void writeOnce(const JointPositions &motion_generator_input)=0
Updates the joint position commands of an active control, with internal controller.
 
virtual void writeOnce(const CartesianPose &motion_generator_input)=0
Updates the cartesian pose commands of an active control, with internal controller.
 
virtual void writeOnce(const JointPositions &, const std::optional< const Torques > &)=0
Updates the joint position and torque commands of an active control.
 
virtual void writeOnce(const CartesianVelocities &, const std::optional< const Torques > &)=0
Updates the cartesian velocity and torque commands of an active control.
 
virtual void writeOnce(const JointVelocities &motion_generator_input)=0
Updates the joint velocity commands of an active control, with internal controller.
 
Stores values for Cartesian pose motion generation.
Definition control_types.h:127
 
Stores values for Cartesian velocity motion generation.
Definition control_types.h:211
 
Stores values for joint position motion generation.
Definition control_types.h:72
 
Stores values for joint velocity motion generation.
Definition control_types.h:99
 
Stores joint-level torque commands without gravity and friction.
Definition control_types.h:45
 
Contains helper types for returning motion generation and joint-level torque commands.
 
Contains exception definitions.
 
Contains the franka::RobotState types.