Public Member Functions | |
| AmtecNode () | |
| bool | getStatus (amtec::GetStatus::Request &req, amtec::GetStatus::Response &resp) |
| bool | halt (amtec::Halt::Request &req, amtec::Halt::Response &resp) |
| bool | home (amtec::Home::Request &req, amtec::Home::Response &resp) |
| void | printModuleState (unsigned int state) |
| bool | reset (amtec::Reset::Request &req, amtec::Reset::Response &resp) |
| bool | setPosition (amtec::SetPosition::Request &req, amtec::SetPosition::Response &resp) |
| bool | setVelocity (amtec::SetVelocity::Request &req, amtec::SetVelocity::Response &resp) |
| bool | spin () |
| bool | sweepPan (amtec::SweepPan::Request &req, amtec::SweepPan::Response &resp) |
| bool | sweepTilt (amtec::SweepTilt::Request &req, amtec::SweepTilt::Response &resp) |
| bool | targetAcceleration (amtec::TargetAcceleration::Request &req, amtec::TargetAcceleration::Response &resp) |
| bool | targetVelocity (amtec::TargetVelocity::Request &req, amtec::TargetVelocity::Response &resp) |
| virtual | ~AmtecNode () |
Public Attributes | |
| amtec_powercube_p | amtec_ |
| std::string | amtec_frame_ |
| boost::mutex | amtec_mutex_ |
| amtec::AmtecState | amtec_pan_state_message_ |
| amtec::AmtecState | amtec_tilt_state_message_ |
| ros::ServiceServer | get_status_srv_ |
| ros::ServiceServer | halt_srv_ |
| ros::ServiceServer | home_srv_ |
| ros::NodeHandle | node_ |
| ros::Publisher | pan_state_pub_ |
| std::string | parent_frame_ |
| tf::Transform | parent_to_amtec_ |
| ros::ServiceServer | reset_srv_ |
| ros::ServiceServer | set_position_srv_ |
| ros::ServiceServer | set_velocity_srv_ |
| ros::ServiceServer | sweep_pan_srv_ |
| ros::ServiceServer | sweep_tilt_srv_ |
| ros::ServiceServer | target_accel_srv_ |
| ros::ServiceServer | target_vel_srv_ |
| tf::TransformBroadcaster | tf_ |
| ros::Publisher | tilt_state_pub_ |
Definition at line 63 of file amtec_node.cpp.
| AmtecNode::AmtecNode | ( | ) | [inline] |
Definition at line 92 of file amtec_node.cpp.
| virtual AmtecNode::~AmtecNode | ( | ) | [inline, virtual] |
Definition at line 215 of file amtec_node.cpp.
| bool AmtecNode::getStatus | ( | amtec::GetStatus::Request & | req, |
| amtec::GetStatus::Response & | resp | ||
| ) | [inline] |
Definition at line 249 of file amtec_node.cpp.
| bool AmtecNode::halt | ( | amtec::Halt::Request & | req, |
| amtec::Halt::Response & | resp | ||
| ) | [inline] |
Definition at line 260 of file amtec_node.cpp.
| bool AmtecNode::home | ( | amtec::Home::Request & | req, |
| amtec::Home::Response & | resp | ||
| ) | [inline] |
Definition at line 270 of file amtec_node.cpp.
| void AmtecNode::printModuleState | ( | unsigned int | state | ) | [inline] |
Definition at line 221 of file amtec_node.cpp.
| bool AmtecNode::reset | ( | amtec::Reset::Request & | req, |
| amtec::Reset::Response & | resp | ||
| ) | [inline] |
Definition at line 280 of file amtec_node.cpp.
| bool AmtecNode::setPosition | ( | amtec::SetPosition::Request & | req, |
| amtec::SetPosition::Response & | resp | ||
| ) | [inline] |
Definition at line 290 of file amtec_node.cpp.
| bool AmtecNode::setVelocity | ( | amtec::SetVelocity::Request & | req, |
| amtec::SetVelocity::Response & | resp | ||
| ) | [inline] |
Definition at line 304 of file amtec_node.cpp.
| bool AmtecNode::spin | ( | ) | [inline] |
Definition at line 352 of file amtec_node.cpp.
| bool AmtecNode::sweepPan | ( | amtec::SweepPan::Request & | req, |
| amtec::SweepPan::Response & | resp | ||
| ) | [inline] |
Definition at line 334 of file amtec_node.cpp.
| bool AmtecNode::sweepTilt | ( | amtec::SweepTilt::Request & | req, |
| amtec::SweepTilt::Response & | resp | ||
| ) | [inline] |
Definition at line 343 of file amtec_node.cpp.
| bool AmtecNode::targetAcceleration | ( | amtec::TargetAcceleration::Request & | req, |
| amtec::TargetAcceleration::Response & | resp | ||
| ) | [inline] |
Definition at line 314 of file amtec_node.cpp.
| bool AmtecNode::targetVelocity | ( | amtec::TargetVelocity::Request & | req, |
| amtec::TargetVelocity::Response & | resp | ||
| ) | [inline] |
Definition at line 324 of file amtec_node.cpp.
Definition at line 68 of file amtec_node.cpp.
| std::string AmtecNode::amtec_frame_ |
Definition at line 89 of file amtec_node.cpp.
| boost::mutex AmtecNode::amtec_mutex_ |
Definition at line 67 of file amtec_node.cpp.
| amtec::AmtecState AmtecNode::amtec_pan_state_message_ |
Definition at line 69 of file amtec_node.cpp.
| amtec::AmtecState AmtecNode::amtec_tilt_state_message_ |
Definition at line 70 of file amtec_node.cpp.
Definition at line 75 of file amtec_node.cpp.
Definition at line 76 of file amtec_node.cpp.
Definition at line 77 of file amtec_node.cpp.
Definition at line 66 of file amtec_node.cpp.
Definition at line 72 of file amtec_node.cpp.
| std::string AmtecNode::parent_frame_ |
Definition at line 88 of file amtec_node.cpp.
Definition at line 87 of file amtec_node.cpp.
Definition at line 78 of file amtec_node.cpp.
Definition at line 79 of file amtec_node.cpp.
Definition at line 80 of file amtec_node.cpp.
Definition at line 83 of file amtec_node.cpp.
Definition at line 84 of file amtec_node.cpp.
Definition at line 81 of file amtec_node.cpp.
Definition at line 82 of file amtec_node.cpp.
Definition at line 86 of file amtec_node.cpp.
Definition at line 73 of file amtec_node.cpp.