Classes | Typedefs | Enumerations | Functions | Variables
franka_hw Namespace Reference

Classes

class  ControllerConflict
 
class  FrankaCartesianPoseHandle
 Handle to read and command a Cartesian pose. More...
 
class  FrankaCartesianVelocityHandle
 Handle to read and command a Cartesian velocity. More...
 
class  FrankaCombinableHW
 A hardware class for a Panda robot based on the ros_control framework. More...
 
class  FrankaCombinedHW
 
class  FrankaHW
 This class wraps the functionality of libfranka for controlling Panda robots into the ros_control framework. More...
 
class  FrankaModelHandle
 Handle to perform calculations using the dynamic model of a robot. More...
 
class  FrankaModelInterface
 Hardware interface to perform calculations using the dynamic model of a robot. More...
 
class  FrankaPoseCartesianInterface
 Hardware interface to command Cartesian poses. More...
 
class  FrankaStateHandle
 Handle to read the complete state of a robot. More...
 
class  FrankaStateInterface
 Hardware interface to read the complete robot state. More...
 
class  FrankaVelocityCartesianInterface
 Hardware interface to command Cartesian velocities. More...
 
class  NoControllerConflict
 
struct  ResourceClaims
 
class  ServiceContainer
 This class serves as container that gathers all possible service interfaces to a libfranka robot instance. More...
 
class  TriggerRate
 

Typedefs

using ArmClaimedMap = std::map< std::string, ResourceClaims >
 
using ResourceWithClaimsMap = std::map< std::string, std::vector< std::vector< std::string >>>
 

Enumerations

enum  ControlMode {
  ControlMode::None = 0, ControlMode::JointTorque = (1 << 0), ControlMode::JointPosition = (1 << 1), ControlMode::JointVelocity = (1 << 2),
  ControlMode::CartesianVelocity = (1 << 3), ControlMode::CartesianPose = (1 << 4)
}
 

Functions

template<typename T >
ros::ServiceServer advertiseService (ros::NodeHandle &node_handle, const std::string &name, std::function< void(typename T::Request &, typename T::Response &)> handler)
 Advertises a service that acts according to the handler function which is used in the service callback. More...
 
string arm_id2 ("panda2")
 
string cp_iface_str ("franka_hw::FrankaPoseCartesianInterface")
 
string cv_iface_str ("franka_hw::FrankaVelocityCartesianInterface")
 
bool findArmIdInResourceId (const std::string &resource_id, std::string *arm_id)
 
bool getArmClaimedMap (ResourceWithClaimsMap &resource_map, ArmClaimedMap &arm_claim_map)
 
ControlMode getControlMode (const std::string &arm_id, ArmClaimedMap &arm_claim_map)
 
ResourceWithClaimsMap getResourceMap (const std::list< hardware_interface::ControllerInfo > &info)
 
bool hasConflictingJointAndCartesianClaim (const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
 
bool hasConflictingMultiClaim (const ResourceWithClaimsMap &resource_map)
 
bool hasTrajectoryClaim (const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
 
 INSTANTIATE_TEST_CASE_P (nonAdmissibleRequests, ControllerConflict,::testing::Values(std::list< ControllerInfo >{no_id_info}, std::list< ControllerInfo >{unknown_iface_info}, std::list< ControllerInfo >{jt_jt_info}, std::list< ControllerInfo >{jp_jp_info}, std::list< ControllerInfo >{jp_jv_info}, std::list< ControllerInfo >{jp_cv_info}, std::list< ControllerInfo >{jp_cp_info}, std::list< ControllerInfo >{jv_jv_info}, std::list< ControllerInfo >{jv_cv_info}, std::list< ControllerInfo >{jv_cp_info}, std::list< ControllerInfo >{cv_cv_info}, std::list< ControllerInfo >{cv_cp_info}, std::list< ControllerInfo >{cp_cp_info}, std::list< ControllerInfo >{jp_jp_jp_info}))
 
 INSTANTIATE_TEST_CASE_P (admissibleRequests, NoControllerConflict,::testing::Values(std::list< ControllerInfo >{jp_info}, std::list< ControllerInfo >{jv_info}, std::list< ControllerInfo >{jt_info}, std::list< ControllerInfo >{cv_info}, std::list< ControllerInfo >{cp_info}, std::list< ControllerInfo >{jt_jp_info}, std::list< ControllerInfo >{jt_jv_info}, std::list< ControllerInfo >{jt_cv_info}, std::list< ControllerInfo >{jt_cp_info}, std::list< ControllerInfo >{cp_info, cp_arm2_info}))
 
string jp_iface_str ("hardware_interface::PositionJointInterface")
 
string jt_iface_str ("hardware_interface::EffortJointInterface")
 
string jv_iface_str ("hardware_interface::VelocityJointInterface")
 
string name_str ("some_controller")
 
hardware_interface::ControllerInfo newInfo (const std::string &name, const std::string &type, const hardware_interface::InterfaceResources &resource1)
 
hardware_interface::ControllerInfo newInfo (const std::string &name, const std::string &type, const hardware_interface::InterfaceResources &resource1, const hardware_interface::InterfaceResources &resource2)
 
hardware_interface::ControllerInfo newInfo (const std::string &name, const std::string &type, const hardware_interface::InterfaceResources &resource1, const hardware_interface::InterfaceResources &resource2, const hardware_interface::InterfaceResources &resource3)
 
constexpr ControlMode operator& (ControlMode left, ControlMode right)
 
constexpr ControlModeoperator&= (ControlMode &left, ControlMode right)
 
std::ostream & operator<< (std::ostream &ostream, ControlMode mode)
 
constexpr ControlMode operator^ (ControlMode left, ControlMode right)
 
constexpr ControlMode operator| (ControlMode left, ControlMode right)
 
constexpr ControlModeoperator|= (ControlMode &left, ControlMode right)
 
constexpr ControlMode operator~ (ControlMode mode)
 
bool partiallyClaimsArmJoints (const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
 
void setCartesianImpedance (franka::Robot &robot, const franka_msgs::SetCartesianImpedance::Request &req, franka_msgs::SetCartesianImpedance::Response &res)
 Callback for the service interface to franka::robot::setCartesianImpedance. More...
 
void setEEFrame (franka::Robot &robot, const franka_msgs::SetEEFrame::Request &req, franka_msgs::SetEEFrame::Response &res)
 Callback for the service interface to franka::robot::setEEFrame. More...
 
void setForceTorqueCollisionBehavior (franka::Robot &robot, const franka_msgs::SetForceTorqueCollisionBehavior::Request &req, franka_msgs::SetForceTorqueCollisionBehavior::Response &res)
 Callback for the service interface to franka::robot::setForceTorqueCollisionBehavior. More...
 
void setFullCollisionBehavior (franka::Robot &robot, const franka_msgs::SetFullCollisionBehavior::Request &req, franka_msgs::SetFullCollisionBehavior::Response &res)
 Callback for the service interface to franka::robot::setFullCollisionBehavior. More...
 
void setJointImpedance (franka::Robot &robot, const franka_msgs::SetJointImpedance::Request &req, franka_msgs::SetJointImpedance::Response &res)
 Callback for the service interface to franka::robot::setJointImpedance. More...
 
void setKFrame (franka::Robot &robot, const franka_msgs::SetKFrame::Request &req, franka_msgs::SetKFrame::Response &res)
 Callback for the service interface to franka::robot::setKFrame. More...
 
void setLoad (franka::Robot &robot, const franka_msgs::SetLoad::Request &req, franka_msgs::SetLoad::Response &res)
 Callback for the service interface to franka::robot::setLoad. More...
 
void setupServices (franka::Robot &robot, ros::NodeHandle &node_handle, ServiceContainer &services)
 Sets up all services relevant for a libfranka robot inside a service container. More...
 
 TEST (FrankaHWTests, InterfacesWorkForReadAndCommand)
 
 TEST (FrankaHWTests, JointLimitInterfacesEnforceLimitsOnCommands)
 
 TEST_P (ControllerConflict, ConflictsForIncompatibleControllers)
 
 TEST_P (NoControllerConflict, DoesNotConflictForCompatibleControllers)
 
 TEST_P (NoControllerConflict, CanPrepareSwitchForCompatibleControllers)
 
string type_str ("SomeControllerClass")
 
string unknown_iface_str ("hardware_interface::UnknownInterface")
 

Variables

set< string > cartesian_arm2_set = {arm_id2 + "_robot"}
 
set< string > cartesian_set = {arm_id + "_robot"}
 
ControllerInfo cp_arm2_info = newInfo(name_str, type_str, cp_arm2_res)
 
InterfaceResources cp_arm2_res (cp_iface_str, cartesian_arm2_set)
 
ControllerInfo cp_cp_info = newInfo(name_str, type_str, cp_res, cp_res)
 
ControllerInfo cp_info = newInfo(name_str, type_str, cp_res)
 
InterfaceResources cp_res (cp_iface_str, cartesian_set)
 
ControllerInfo cv_cp_info = newInfo(name_str, type_str, cv_res, cp_res)
 
ControllerInfo cv_cv_info = newInfo(name_str, type_str, cv_res, cv_res)
 
ControllerInfo cv_info = newInfo(name_str, type_str, cv_res)
 
InterfaceResources cv_res (cv_iface_str, cartesian_set)
 
set< string > joints_set
 
ControllerInfo jp_cp_info = newInfo(name_str, type_str, jp_res, cp_res)
 
ControllerInfo jp_cv_info = newInfo(name_str, type_str, jp_res, cv_res)
 
ControllerInfo jp_info = newInfo(name_str, type_str, jp_res)
 
ControllerInfo jp_jp_info = newInfo(name_str, type_str, jp_res, jp_res)
 
ControllerInfo jp_jp_jp_info = newInfo(name_str, type_str, jp_res, jp_res, jp_res)
 
ControllerInfo jp_jv_info = newInfo(name_str, type_str, jp_res, jv_res)
 
InterfaceResources jp_res (jp_iface_str, joints_set)
 
ControllerInfo jt_cp_info = newInfo(name_str, type_str, jt_res, cp_res)
 
ControllerInfo jt_cv_info = newInfo(name_str, type_str, jt_res, cv_res)
 
ControllerInfo jt_info = newInfo(name_str, type_str, jt_res)
 
ControllerInfo jt_jp_info = newInfo(name_str, type_str, jt_res, jp_res)
 
ControllerInfo jt_jt_info = newInfo(name_str, type_str, jt_res, jt_res)
 
ControllerInfo jt_jv_info = newInfo(name_str, type_str, jt_res, jv_res)
 
InterfaceResources jt_res (jt_iface_str, joints_set)
 
ControllerInfo jv_cp_info = newInfo(name_str, type_str, jv_res, cp_res)
 
ControllerInfo jv_cv_info = newInfo(name_str, type_str, jv_res, cv_res)
 
ControllerInfo jv_info = newInfo(name_str, type_str, jv_res)
 
ControllerInfo jv_jv_info = newInfo(name_str, type_str, jv_res, jv_res)
 
InterfaceResources jv_res (jv_iface_str, joints_set)
 
ControllerInfo no_id_info = newInfo(name_str, type_str, no_id_res)
 
InterfaceResources no_id_res (jp_iface_str, no_id_set)
 
set< string > no_id_set = {"joint1"}
 
ControllerInfo unknown_iface_info = newInfo(name_str, type_str, unknown_iface_res)
 
InterfaceResources unknown_iface_res (unknown_iface_str, joints_set)
 

Typedef Documentation

using franka_hw::ArmClaimedMap = typedef std::map<std::string, ResourceClaims>

Definition at line 26 of file resource_helpers.h.

using franka_hw::ResourceWithClaimsMap = typedef std::map<std::string, std::vector<std::vector<std::string>>>

Definition at line 16 of file resource_helpers.h.

Enumeration Type Documentation

Enumerator
None 
JointTorque 
JointPosition 
JointVelocity 
CartesianVelocity 
CartesianPose 

Definition at line 10 of file control_mode.h.

Function Documentation

template<typename T >
ros::ServiceServer franka_hw::advertiseService ( ros::NodeHandle node_handle,
const std::string &  name,
std::function< void(typename T::Request &, typename T::Response &)>  handler 
)

Advertises a service that acts according to the handler function which is used in the service callback.

Parameters
[in]node_handleThe NodeHandle in the namespace at which to advertise the service.
[in]nameThe name of the service.
[in]handlerThe callback method for the service.
Returns
The service server.

Definition at line 32 of file services.h.

string franka_hw::arm_id2 ( "panda2"  )
string franka_hw::cp_iface_str ( "franka_hw::FrankaPoseCartesianInterface"  )
string franka_hw::cv_iface_str ( "franka_hw::FrankaVelocityCartesianInterface"  )
bool franka_hw::findArmIdInResourceId ( const std::string &  resource_id,
std::string *  arm_id 
)

Definition at line 9 of file resource_helpers.cpp.

bool franka_hw::getArmClaimedMap ( ResourceWithClaimsMap resource_map,
ArmClaimedMap arm_claim_map 
)

Definition at line 41 of file resource_helpers.cpp.

ControlMode franka_hw::getControlMode ( const std::string &  arm_id,
ArmClaimedMap arm_claim_map 
)

Definition at line 78 of file resource_helpers.cpp.

ResourceWithClaimsMap franka_hw::getResourceMap ( const std::list< hardware_interface::ControllerInfo > &  info)

Definition at line 23 of file resource_helpers.cpp.

bool franka_hw::hasConflictingJointAndCartesianClaim ( const ArmClaimedMap arm_claim_map,
const std::string &  arm_id 
)

Definition at line 168 of file resource_helpers.cpp.

bool franka_hw::hasConflictingMultiClaim ( const ResourceWithClaimsMap resource_map)

Definition at line 138 of file resource_helpers.cpp.

bool franka_hw::hasTrajectoryClaim ( const ArmClaimedMap arm_claim_map,
const std::string &  arm_id 
)

Definition at line 206 of file resource_helpers.cpp.

franka_hw::INSTANTIATE_TEST_CASE_P ( nonAdmissibleRequests  ,
ControllerConflict  ,
::testing::Values(std::list< ControllerInfo >{no_id_info}, std::list< ControllerInfo >{unknown_iface_info}, std::list< ControllerInfo >{jt_jt_info}, std::list< ControllerInfo >{jp_jp_info}, std::list< ControllerInfo >{jp_jv_info}, std::list< ControllerInfo >{jp_cv_info}, std::list< ControllerInfo >{jp_cp_info}, std::list< ControllerInfo >{jv_jv_info}, std::list< ControllerInfo >{jv_cv_info}, std::list< ControllerInfo >{jv_cp_info}, std::list< ControllerInfo >{cv_cv_info}, std::list< ControllerInfo >{cv_cp_info}, std::list< ControllerInfo >{cp_cp_info}, std::list< ControllerInfo >{jp_jp_jp_info})   
)
franka_hw::INSTANTIATE_TEST_CASE_P ( admissibleRequests  ,
NoControllerConflict  ,
::testing::Values(std::list< ControllerInfo >{jp_info}, std::list< ControllerInfo >{jv_info}, std::list< ControllerInfo >{jt_info}, std::list< ControllerInfo >{cv_info}, std::list< ControllerInfo >{cp_info}, std::list< ControllerInfo >{jt_jp_info}, std::list< ControllerInfo >{jt_jv_info}, std::list< ControllerInfo >{jt_cv_info}, std::list< ControllerInfo >{jt_cp_info}, std::list< ControllerInfo >{cp_info, cp_arm2_info})   
)
string franka_hw::jp_iface_str ( "hardware_interface::PositionJointInterface"  )
string franka_hw::jt_iface_str ( "hardware_interface::EffortJointInterface"  )
string franka_hw::jv_iface_str ( "hardware_interface::VelocityJointInterface"  )
string franka_hw::name_str ( "some_controller"  )
hardware_interface::ControllerInfo franka_hw::newInfo ( const std::string &  name,
const std::string &  type,
const hardware_interface::InterfaceResources resource1 
)

Definition at line 33 of file franka_hw_controller_switching_test.cpp.

hardware_interface::ControllerInfo franka_hw::newInfo ( const std::string &  name,
const std::string &  type,
const hardware_interface::InterfaceResources resource1,
const hardware_interface::InterfaceResources resource2 
)

Definition at line 45 of file franka_hw_controller_switching_test.cpp.

hardware_interface::ControllerInfo franka_hw::newInfo ( const std::string &  name,
const std::string &  type,
const hardware_interface::InterfaceResources resource1,
const hardware_interface::InterfaceResources resource2,
const hardware_interface::InterfaceResources resource3 
)

Definition at line 55 of file franka_hw_controller_switching_test.cpp.

constexpr ControlMode franka_hw::operator& ( ControlMode  left,
ControlMode  right 
)

Definition at line 22 of file control_mode.h.

constexpr ControlMode& franka_hw::operator&= ( ControlMode left,
ControlMode  right 
)

Definition at line 41 of file control_mode.h.

std::ostream & franka_hw::operator<< ( std::ostream &  ostream,
ControlMode  mode 
)

Definition at line 12 of file control_mode.cpp.

constexpr ControlMode franka_hw::operator^ ( ControlMode  left,
ControlMode  right 
)

Definition at line 32 of file control_mode.h.

constexpr ControlMode franka_hw::operator| ( ControlMode  left,
ControlMode  right 
)

Definition at line 27 of file control_mode.h.

constexpr ControlMode& franka_hw::operator|= ( ControlMode left,
ControlMode  right 
)

Definition at line 45 of file control_mode.h.

constexpr ControlMode franka_hw::operator~ ( ControlMode  mode)

Definition at line 37 of file control_mode.h.

bool franka_hw::partiallyClaimsArmJoints ( const ArmClaimedMap arm_claim_map,
const std::string &  arm_id 
)

Definition at line 187 of file resource_helpers.cpp.

void franka_hw::setCartesianImpedance ( franka::Robot robot,
const franka_msgs::SetCartesianImpedance::Request &  req,
franka_msgs::SetCartesianImpedance::Response &  res 
)

Callback for the service interface to franka::robot::setCartesianImpedance.

Parameters
[in]robotThe libfranka robot for which to set up the service.
[in]reqThe service request.
[out]resThe service response.

Definition at line 40 of file services.cpp.

void franka_hw::setEEFrame ( franka::Robot robot,
const franka_msgs::SetEEFrame::Request &  req,
franka_msgs::SetEEFrame::Response &  res 
)

Callback for the service interface to franka::robot::setEEFrame.

Parameters
[in]robotThe libfranka robot for which to set up the service.
[in]reqThe service request.
[out]resThe service response.

Definition at line 57 of file services.cpp.

void franka_hw::setForceTorqueCollisionBehavior ( franka::Robot robot,
const franka_msgs::SetForceTorqueCollisionBehavior::Request &  req,
franka_msgs::SetForceTorqueCollisionBehavior::Response &  res 
)

Callback for the service interface to franka::robot::setForceTorqueCollisionBehavior.

Parameters
[in]robotThe libfranka robot for which to set up the service.
[in]reqThe service request.
[out]resThe service response.

Definition at line 73 of file services.cpp.

void franka_hw::setFullCollisionBehavior ( franka::Robot robot,
const franka_msgs::SetFullCollisionBehavior::Request &  req,
franka_msgs::SetFullCollisionBehavior::Response &  res 
)

Callback for the service interface to franka::robot::setFullCollisionBehavior.

Parameters
[in]robotThe libfranka robot for which to set up the service.
[in]reqThe service request.
[out]resThe service response.

Definition at line 95 of file services.cpp.

void franka_hw::setJointImpedance ( franka::Robot robot,
const franka_msgs::SetJointImpedance::Request &  req,
franka_msgs::SetJointImpedance::Response &  res 
)

Callback for the service interface to franka::robot::setJointImpedance.

Parameters
[in]robotThe libfranka robot for which to set up the service.
[in]reqThe service request.
[out]resThe service response.

Definition at line 49 of file services.cpp.

void franka_hw::setKFrame ( franka::Robot robot,
const franka_msgs::SetKFrame::Request &  req,
franka_msgs::SetKFrame::Response &  res 
)

Callback for the service interface to franka::robot::setKFrame.

Parameters
[in]robotThe libfranka robot for which to set up the service.
[in]reqThe service request.
[out]resThe service response.

Definition at line 65 of file services.cpp.

void franka_hw::setLoad ( franka::Robot robot,
const franka_msgs::SetLoad::Request &  req,
franka_msgs::SetLoad::Response &  res 
)

Callback for the service interface to franka::robot::setLoad.

Parameters
[in]robotThe libfranka robot for which to set up the service.
[in]reqThe service request.
[out]resThe service response.

Definition at line 133 of file services.cpp.

void franka_hw::setupServices ( franka::Robot robot,
ros::NodeHandle node_handle,
ServiceContainer services 
)

Sets up all services relevant for a libfranka robot inside a service container.

Parameters
[in]robotThe libfranka robot for which to set up services interfaces.
[in]node_handleThe NodeHandle in the namespace at which to advertise the services.
[in]servicesThe container to store the service servers.

Definition at line 7 of file services.cpp.

franka_hw::TEST ( FrankaHWTests  ,
InterfacesWorkForReadAndCommand   
)

Definition at line 25 of file franka_hw_interfaces_test.cpp.

franka_hw::TEST ( FrankaHWTests  ,
JointLimitInterfacesEnforceLimitsOnCommands   
)

Definition at line 75 of file franka_hw_interfaces_test.cpp.

franka_hw::TEST_P ( ControllerConflict  ,
ConflictsForIncompatibleControllers   
)

Definition at line 184 of file franka_hw_controller_switching_test.cpp.

franka_hw::TEST_P ( NoControllerConflict  ,
DoesNotConflictForCompatibleControllers   
)

Definition at line 188 of file franka_hw_controller_switching_test.cpp.

franka_hw::TEST_P ( NoControllerConflict  ,
CanPrepareSwitchForCompatibleControllers   
)

Definition at line 192 of file franka_hw_controller_switching_test.cpp.

string franka_hw::type_str ( "SomeControllerClass"  )
string franka_hw::unknown_iface_str ( "hardware_interface::UnknownInterface"  )

Variable Documentation

set<string> franka_hw::cartesian_arm2_set = {arm_id2 + "_robot"}

Definition at line 119 of file franka_hw_controller_switching_test.cpp.

set<string> franka_hw::cartesian_set = {arm_id + "_robot"}

Definition at line 118 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::cp_arm2_info = newInfo(name_str, type_str, cp_arm2_res)

Definition at line 129 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::cp_cp_info = newInfo(name_str, type_str, cp_res, cp_res)

Definition at line 142 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::cp_info = newInfo(name_str, type_str, cp_res)

Definition at line 148 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::cv_cp_info = newInfo(name_str, type_str, cv_res, cp_res)

Definition at line 141 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::cv_cv_info = newInfo(name_str, type_str, cv_res, cv_res)

Definition at line 140 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::cv_info = newInfo(name_str, type_str, cv_res)

Definition at line 147 of file franka_hw_controller_switching_test.cpp.

set<string> franka_hw::joints_set
Initial value:
= {joint_names[0], joint_names[1], joint_names[2], joint_names[3],
joint_names[4], joint_names[5], joint_names[6]}
std::array< std::string, 7 > joint_names

Definition at line 116 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jp_cp_info = newInfo(name_str, type_str, jp_res, cp_res)

Definition at line 136 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jp_cv_info = newInfo(name_str, type_str, jp_res, cv_res)

Definition at line 135 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jp_info = newInfo(name_str, type_str, jp_res)

Definition at line 144 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jp_jp_info = newInfo(name_str, type_str, jp_res, jp_res)

Definition at line 133 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jp_jp_jp_info = newInfo(name_str, type_str, jp_res, jp_res, jp_res)

Definition at line 143 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jp_jv_info = newInfo(name_str, type_str, jp_res, jv_res)

Definition at line 134 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jt_cp_info = newInfo(name_str, type_str, jt_res, cp_res)

Definition at line 152 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jt_cv_info = newInfo(name_str, type_str, jt_res, cv_res)

Definition at line 151 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jt_info = newInfo(name_str, type_str, jt_res)

Definition at line 146 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jt_jp_info = newInfo(name_str, type_str, jt_res, jp_res)

Definition at line 149 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jt_jt_info = newInfo(name_str, type_str, jt_res, jt_res)

Definition at line 132 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jt_jv_info = newInfo(name_str, type_str, jt_res, jv_res)

Definition at line 150 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jv_cp_info = newInfo(name_str, type_str, jv_res, cp_res)

Definition at line 139 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jv_cv_info = newInfo(name_str, type_str, jv_res, cv_res)

Definition at line 138 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jv_info = newInfo(name_str, type_str, jv_res)

Definition at line 145 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::jv_jv_info = newInfo(name_str, type_str, jv_res, jv_res)

Definition at line 137 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::no_id_info = newInfo(name_str, type_str, no_id_res)

Definition at line 130 of file franka_hw_controller_switching_test.cpp.

InterfaceResources franka_hw::no_id_res(jp_iface_str, no_id_set)
set<string> franka_hw::no_id_set = {"joint1"}

Definition at line 120 of file franka_hw_controller_switching_test.cpp.

ControllerInfo franka_hw::unknown_iface_info = newInfo(name_str, type_str, unknown_iface_res)

Definition at line 131 of file franka_hw_controller_switching_test.cpp.

InterfaceResources franka_hw::unknown_iface_res(unknown_iface_str, joints_set)


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