Public Member Functions | Private Member Functions | Private Attributes | List of all members
franka_control::FrankaStateController Class Reference

Controller to publish the robot state as ROS topics. More...

#include <franka_state_controller.h>

Inheritance diagram for franka_control::FrankaStateController:
Inheritance graph
[legend]

Public Member Functions

 FrankaStateController ()=default
 Creates an instance of a FrankaStateController. More...
 
bool init (hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &root_node_handle, ros::NodeHandle &controller_node_handle) override
 Initializes the controller with interfaces and publishers. More...
 
void update (const ros::Time &time, const ros::Duration &period) override
 Reads the current robot state from the franka_hw::FrankaStateInterface and publishes it. More...
 
- Public Member Functions inherited from controller_interface::MultiInterfaceController< franka_hw::FrankaStateInterface >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
virtual ~MultiInterfaceController ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
virtual void starting (const ros::Time &)
 
virtual void starting (const ros::Time &)
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
virtual void stopping (const ros::Time &)
 
virtual void stopping (const ros::Time &)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual ~ControllerBase ()
 

Private Member Functions

void publishExternalWrench (const ros::Time &time)
 
void publishFrankaStates (const ros::Time &time)
 
void publishJointStates (const ros::Time &time)
 
void publishTransforms (const ros::Time &time)
 

Private Attributes

std::string arm_id_
 
std::unique_ptr< franka_hw::FrankaStateHandlefranka_state_handle_ {}
 
franka_hw::FrankaStateInterfacefranka_state_interface_ {}
 
std::vector< std::string > joint_names_
 
realtime_tools::RealtimePublisher< geometry_msgs::WrenchStamped > publisher_external_wrench_
 
realtime_tools::RealtimePublisher< franka_msgs::FrankaState > publisher_franka_states_
 
realtime_tools::RealtimePublisher< sensor_msgs::JointState > publisher_joint_states_
 
realtime_tools::RealtimePublisher< sensor_msgs::JointState > publisher_joint_states_desired_
 
realtime_tools::RealtimePublisher< tf2_msgs::TFMessage > publisher_transforms_
 
franka::RobotState robot_state_
 
uint64_t sequence_number_ = 0
 
franka_hw::TriggerRate trigger_publish_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< franka_hw::FrankaStateInterface >
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< franka_hw::FrankaStateInterface >
static void clearClaims (hardware_interface::RobotHW *robot_hw)
 
static void extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out)
 
static bool hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw)
 
static void populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< franka_hw::FrankaStateInterface >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

Controller to publish the robot state as ROS topics.

Definition at line 23 of file franka_state_controller.h.

Constructor & Destructor Documentation

franka_control::FrankaStateController::FrankaStateController ( )
default

Creates an instance of a FrankaStateController.

Member Function Documentation

bool franka_control::FrankaStateController::init ( hardware_interface::RobotHW robot_hardware,
ros::NodeHandle root_node_handle,
ros::NodeHandle controller_node_handle 
)
overridevirtual

Initializes the controller with interfaces and publishers.

Parameters
[in]robot_hardwareRobotHW instance to get a franka_hw::FrankaStateInterface from.
[in]root_node_handleNode handle in the controller_manager namespace.
[in]controller_node_handleNode handle in the controller namespace.

Reimplemented from controller_interface::MultiInterfaceController< franka_hw::FrankaStateInterface >.

Definition at line 138 of file franka_state_controller.cpp.

void franka_control::FrankaStateController::publishExternalWrench ( const ros::Time time)
private

Definition at line 445 of file franka_state_controller.cpp.

void franka_control::FrankaStateController::publishFrankaStates ( const ros::Time time)
private

Definition at line 239 of file franka_state_controller.cpp.

void franka_control::FrankaStateController::publishJointStates ( const ros::Time time)
private

Definition at line 397 of file franka_state_controller.cpp.

void franka_control::FrankaStateController::publishTransforms ( const ros::Time time)
private

Definition at line 430 of file franka_state_controller.cpp.

void franka_control::FrankaStateController::update ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Reads the current robot state from the franka_hw::FrankaStateInterface and publishes it.

Parameters
[in]timeCurrent ROS time.
[in]periodTime since the last update.

Implements controller_interface::ControllerBase.

Definition at line 228 of file franka_state_controller.cpp.

Member Data Documentation

std::string franka_control::FrankaStateController::arm_id_
private

Definition at line 56 of file franka_state_controller.h.

std::unique_ptr<franka_hw::FrankaStateHandle> franka_control::FrankaStateController::franka_state_handle_ {}
private

Definition at line 59 of file franka_state_controller.h.

franka_hw::FrankaStateInterface* franka_control::FrankaStateController::franka_state_interface_ {}
private

Definition at line 58 of file franka_state_controller.h.

std::vector<std::string> franka_control::FrankaStateController::joint_names_
private

Definition at line 69 of file franka_state_controller.h.

realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped> franka_control::FrankaStateController::publisher_external_wrench_
private

Definition at line 65 of file franka_state_controller.h.

realtime_tools::RealtimePublisher<franka_msgs::FrankaState> franka_control::FrankaStateController::publisher_franka_states_
private

Definition at line 62 of file franka_state_controller.h.

realtime_tools::RealtimePublisher<sensor_msgs::JointState> franka_control::FrankaStateController::publisher_joint_states_
private

Definition at line 63 of file franka_state_controller.h.

realtime_tools::RealtimePublisher<sensor_msgs::JointState> franka_control::FrankaStateController::publisher_joint_states_desired_
private

Definition at line 64 of file franka_state_controller.h.

realtime_tools::RealtimePublisher<tf2_msgs::TFMessage> franka_control::FrankaStateController::publisher_transforms_
private

Definition at line 61 of file franka_state_controller.h.

franka::RobotState franka_control::FrankaStateController::robot_state_
private

Definition at line 67 of file franka_state_controller.h.

uint64_t franka_control::FrankaStateController::sequence_number_ = 0
private

Definition at line 68 of file franka_state_controller.h.

franka_hw::TriggerRate franka_control::FrankaStateController::trigger_publish_
private

Definition at line 66 of file franka_state_controller.h.


The documentation for this class was generated from the following files:


franka_control
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:10