Public Member Functions | |
| void | executeCB (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal) |
| NodeClass () | |
| void | publishJointState () |
| bool | srvCallback_Init (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
| bool | srvCallback_Recover (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
| bool | srvCallback_SetDefaultVel (cob_srvs::SetFloat::Request &req, cob_srvs::SetFloat::Response &res) |
| Executes the service callback for set_default_vel. | |
| bool | srvCallback_SetOperationMode (cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res) |
| Executes the service callback for set_operation_mode. | |
| bool | srvCallback_Stop (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
| void | updateCommands () |
| ~NodeClass () | |
Public Attributes | |
| std::string | action_name_ |
| double | ActualPos_ |
| double | ActualVel_ |
| actionlib::SimpleActionServer < control_msgs::FollowJointTrajectoryAction > | as_ |
| ElmoCtrl * | CamAxis_ |
| ElmoCtrlParams * | CamAxisParams_ |
| int | CanBaudrate_ |
| std::string | CanDevice_ |
| std::string | CanIniFile_ |
| int | EnoderIncrementsPerRevMot_ |
| control_msgs::FollowJointTrajectoryFeedback | feedback_ |
| bool | finished_ |
| double | GearRatio_ |
| double | GoalPos_ |
| int | HomingDigIn_ |
| int | HomingDir_ |
| bool | isError_ |
| bool | isInitialized_ |
| std::string | JointName_ |
| double | LowerLimit_ |
| double | MaxVel_ |
| int | ModID_ |
| int | MotorDirection_ |
| ros::NodeHandle | n_ |
| ros::NodeHandle | n_private_ |
| double | Offset_ |
| std::string | operationMode_ |
| control_msgs::FollowJointTrajectoryResult | result_ |
| ros::ServiceServer | srvServer_Init_ |
| ros::ServiceServer | srvServer_Recover_ |
| ros::ServiceServer | srvServer_SetDefaultVel_ |
| ros::ServiceServer | srvServer_SetOperationMode_ |
| ros::ServiceServer | srvServer_Stop_ |
| ros::Publisher | topicPub_ControllerState_ |
| ros::Publisher | topicPub_Diagnostic_ |
| ros::Publisher | topicPub_JointState_ |
| ros::Subscriber | topicSub_JointCommand_ |
| trajectory_msgs::JointTrajectory | traj_ |
| trajectory_msgs::JointTrajectoryPoint | traj_point_ |
| unsigned int | traj_point_nr_ |
| double | UpperLimit_ |
Definition at line 81 of file cob_head_axis.cpp.
| NodeClass::NodeClass | ( | ) | [inline] |
Definition at line 144 of file cob_head_axis.cpp.
| NodeClass::~NodeClass | ( | ) | [inline] |
Definition at line 252 of file cob_head_axis.cpp.
| void NodeClass::executeCB | ( | const control_msgs::FollowJointTrajectoryGoalConstPtr & | goal | ) | [inline] |
Definition at line 257 of file cob_head_axis.cpp.
| void NodeClass::publishJointState | ( | ) | [inline] |
Definition at line 476 of file cob_head_axis.cpp.
| bool NodeClass::srvCallback_Init | ( | std_srvs::Trigger::Request & | req, |
| std_srvs::Trigger::Response & | res | ||
| ) | [inline] |
Definition at line 307 of file cob_head_axis.cpp.
| bool NodeClass::srvCallback_Recover | ( | std_srvs::Trigger::Request & | req, |
| std_srvs::Trigger::Response & | res | ||
| ) | [inline] |
Definition at line 359 of file cob_head_axis.cpp.
| bool NodeClass::srvCallback_SetDefaultVel | ( | cob_srvs::SetFloat::Request & | req, |
| cob_srvs::SetFloat::Response & | res | ||
| ) | [inline] |
Executes the service callback for set_default_vel.
Sets the default velocity.
| req | Service request |
| res | Service response |
Definition at line 407 of file cob_head_axis.cpp.
| bool NodeClass::srvCallback_SetOperationMode | ( | cob_srvs::SetString::Request & | req, |
| cob_srvs::SetString::Response & | res | ||
| ) | [inline] |
Executes the service callback for set_operation_mode.
Changes the operation mode.
| req | Service request |
| res | Service response |
Definition at line 391 of file cob_head_axis.cpp.
| bool NodeClass::srvCallback_Stop | ( | std_srvs::Trigger::Request & | req, |
| std_srvs::Trigger::Response & | res | ||
| ) | [inline] |
Definition at line 338 of file cob_head_axis.cpp.
| void NodeClass::updateCommands | ( | ) | [inline] |
Definition at line 419 of file cob_head_axis.cpp.
| std::string NodeClass::action_name_ |
Definition at line 109 of file cob_head_axis.cpp.
| double NodeClass::ActualPos_ |
Definition at line 136 of file cob_head_axis.cpp.
| double NodeClass::ActualVel_ |
Definition at line 137 of file cob_head_axis.cpp.
| actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> NodeClass::as_ |
Definition at line 108 of file cob_head_axis.cpp.
Definition at line 114 of file cob_head_axis.cpp.
Definition at line 115 of file cob_head_axis.cpp.
Definition at line 119 of file cob_head_axis.cpp.
| std::string NodeClass::CanDevice_ |
Definition at line 117 of file cob_head_axis.cpp.
| std::string NodeClass::CanIniFile_ |
Definition at line 118 of file cob_head_axis.cpp.
Definition at line 129 of file cob_head_axis.cpp.
| control_msgs::FollowJointTrajectoryFeedback NodeClass::feedback_ |
Definition at line 110 of file cob_head_axis.cpp.
| bool NodeClass::finished_ |
Definition at line 135 of file cob_head_axis.cpp.
| double NodeClass::GearRatio_ |
Definition at line 130 of file cob_head_axis.cpp.
| double NodeClass::GoalPos_ |
Definition at line 138 of file cob_head_axis.cpp.
Definition at line 121 of file cob_head_axis.cpp.
Definition at line 120 of file cob_head_axis.cpp.
| bool NodeClass::isError_ |
Definition at line 134 of file cob_head_axis.cpp.
Definition at line 133 of file cob_head_axis.cpp.
| std::string NodeClass::JointName_ |
Definition at line 132 of file cob_head_axis.cpp.
| double NodeClass::LowerLimit_ |
Definition at line 125 of file cob_head_axis.cpp.
| double NodeClass::MaxVel_ |
Definition at line 122 of file cob_head_axis.cpp.
Definition at line 123 of file cob_head_axis.cpp.
Definition at line 128 of file cob_head_axis.cpp.
Definition at line 86 of file cob_head_axis.cpp.
Definition at line 87 of file cob_head_axis.cpp.
| double NodeClass::Offset_ |
Definition at line 127 of file cob_head_axis.cpp.
| std::string NodeClass::operationMode_ |
Definition at line 124 of file cob_head_axis.cpp.
| control_msgs::FollowJointTrajectoryResult NodeClass::result_ |
Definition at line 111 of file cob_head_axis.cpp.
Definition at line 98 of file cob_head_axis.cpp.
Definition at line 100 of file cob_head_axis.cpp.
Definition at line 102 of file cob_head_axis.cpp.
Definition at line 101 of file cob_head_axis.cpp.
Definition at line 99 of file cob_head_axis.cpp.
Definition at line 91 of file cob_head_axis.cpp.
Definition at line 92 of file cob_head_axis.cpp.
Definition at line 90 of file cob_head_axis.cpp.
Definition at line 95 of file cob_head_axis.cpp.
| trajectory_msgs::JointTrajectory NodeClass::traj_ |
Definition at line 139 of file cob_head_axis.cpp.
| trajectory_msgs::JointTrajectoryPoint NodeClass::traj_point_ |
Definition at line 140 of file cob_head_axis.cpp.
| unsigned int NodeClass::traj_point_nr_ |
Definition at line 141 of file cob_head_axis.cpp.
| double NodeClass::UpperLimit_ |
Definition at line 126 of file cob_head_axis.cpp.