#include <JointState.h>
Public Types | |
typedef double | _current_pos_type |
typedef double | _error_type |
typedef double | _goal_pos_type |
typedef ::std_msgs::Header_ < ContainerAllocator > | _header_type |
typedef uint8_t | _is_moving_type |
typedef double | _load_type |
typedef std::vector< int32_t, typename ContainerAllocator::template rebind< int32_t >::other > | _motor_ids_type |
typedef std::vector< int32_t, typename ContainerAllocator::template rebind< int32_t >::other > | _motor_temps_type |
typedef std::basic_string < char, std::char_traits< char > , typename ContainerAllocator::template rebind< char >::other > | _name_type |
typedef double | _velocity_type |
typedef boost::shared_ptr < ::dynamixel_msgs::JointState_ < ContainerAllocator > const > | ConstPtr |
typedef boost::shared_ptr < ::dynamixel_msgs::JointState_ < ContainerAllocator > > | Ptr |
typedef JointState_ < ContainerAllocator > | Type |
Public Member Functions | |
JointState_ () | |
JointState_ (const ContainerAllocator &_alloc) | |
Public Attributes | |
boost::shared_ptr< std::map < std::string, std::string > > | __connection_header |
double | current_pos |
double | error |
double | goal_pos |
::std_msgs::Header_ < ContainerAllocator > | header |
uint8_t | is_moving |
double | load |
std::vector< int32_t, typename ContainerAllocator::template rebind< int32_t >::other > | motor_ids |
std::vector< int32_t, typename ContainerAllocator::template rebind< int32_t >::other > | motor_temps |
std::basic_string< char, std::char_traits< char > , typename ContainerAllocator::template rebind< char >::other > | name |
double | velocity |
Definition at line 22 of file JointState.h.
typedef double dynamixel_msgs::JointState_< ContainerAllocator >::_current_pos_type |
Definition at line 68 of file JointState.h.
typedef double dynamixel_msgs::JointState_< ContainerAllocator >::_error_type |
Definition at line 71 of file JointState.h.
typedef double dynamixel_msgs::JointState_< ContainerAllocator >::_goal_pos_type |
Definition at line 65 of file JointState.h.
typedef ::std_msgs::Header_<ContainerAllocator> dynamixel_msgs::JointState_< ContainerAllocator >::_header_type |
Definition at line 53 of file JointState.h.
typedef uint8_t dynamixel_msgs::JointState_< ContainerAllocator >::_is_moving_type |
Definition at line 80 of file JointState.h.
typedef double dynamixel_msgs::JointState_< ContainerAllocator >::_load_type |
Definition at line 77 of file JointState.h.
typedef std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > dynamixel_msgs::JointState_< ContainerAllocator >::_motor_ids_type |
Definition at line 59 of file JointState.h.
typedef std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > dynamixel_msgs::JointState_< ContainerAllocator >::_motor_temps_type |
Definition at line 62 of file JointState.h.
typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > dynamixel_msgs::JointState_< ContainerAllocator >::_name_type |
Definition at line 56 of file JointState.h.
typedef double dynamixel_msgs::JointState_< ContainerAllocator >::_velocity_type |
Definition at line 74 of file JointState.h.
typedef boost::shared_ptr< ::dynamixel_msgs::JointState_<ContainerAllocator> const> dynamixel_msgs::JointState_< ContainerAllocator >::ConstPtr |
Definition at line 85 of file JointState.h.
typedef boost::shared_ptr< ::dynamixel_msgs::JointState_<ContainerAllocator> > dynamixel_msgs::JointState_< ContainerAllocator >::Ptr |
Definition at line 84 of file JointState.h.
typedef JointState_<ContainerAllocator> dynamixel_msgs::JointState_< ContainerAllocator >::Type |
Definition at line 23 of file JointState.h.
dynamixel_msgs::JointState_< ContainerAllocator >::JointState_ | ( | ) | [inline] |
Definition at line 25 of file JointState.h.
dynamixel_msgs::JointState_< ContainerAllocator >::JointState_ | ( | const ContainerAllocator & | _alloc | ) | [inline] |
Definition at line 39 of file JointState.h.
boost::shared_ptr<std::map<std::string, std::string> > dynamixel_msgs::JointState_< ContainerAllocator >::__connection_header |
Definition at line 86 of file JointState.h.
double dynamixel_msgs::JointState_< ContainerAllocator >::current_pos |
Definition at line 69 of file JointState.h.
double dynamixel_msgs::JointState_< ContainerAllocator >::error |
Definition at line 72 of file JointState.h.
double dynamixel_msgs::JointState_< ContainerAllocator >::goal_pos |
Definition at line 66 of file JointState.h.
::std_msgs::Header_<ContainerAllocator> dynamixel_msgs::JointState_< ContainerAllocator >::header |
Definition at line 54 of file JointState.h.
uint8_t dynamixel_msgs::JointState_< ContainerAllocator >::is_moving |
Definition at line 81 of file JointState.h.
double dynamixel_msgs::JointState_< ContainerAllocator >::load |
Definition at line 78 of file JointState.h.
std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > dynamixel_msgs::JointState_< ContainerAllocator >::motor_ids |
Definition at line 60 of file JointState.h.
std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > dynamixel_msgs::JointState_< ContainerAllocator >::motor_temps |
Definition at line 63 of file JointState.h.
std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > dynamixel_msgs::JointState_< ContainerAllocator >::name |
Definition at line 57 of file JointState.h.
double dynamixel_msgs::JointState_< ContainerAllocator >::velocity |
Definition at line 75 of file JointState.h.