#include <PlaDyPosNode.hpp>
Public Member Functions | |
void | configure (ros::NodeHandle &nh, ros::NodeHandle &ph) |
PlaDyPosNode () | |
~PlaDyPosNode () | |
Protected Member Functions | |
void | driverMsg (const int n[4]) |
void | dynrec (pladypos::ThrusterMappingConfig &config, uint32_t level) |
void | onReply (const boost::system::error_code &error, const size_t &transferred) |
void | onTau (const auv_msgs::BodyForceReq::ConstPtr tau) |
void | pubDiagnostics () |
void | safetyTest () |
void | start_receive () |
Protected Attributes | |
ScaleAllocation | allocator |
Eigen::Matrix< float, 3, 4 > | B |
ros::Publisher | diag |
ros::Publisher | info |
boost::asio::io_service | io |
boost::thread | iorunner |
int | lastRevs [4] |
ros::Time | lastTau |
boost::asio::serial_port | port |
bool | revControl |
boost::thread | safety |
boost::asio::streambuf | sbuffer |
boost::array< float, 6 > | sensors |
boost::mutex | serialMux |
dynamic_reconfigure::Server < pladypos::ThrusterMappingConfig > | server |
ros::Subscriber | tau |
ros::Publisher | tauAch |
double | timeout |
Private Types | |
enum | { current0, current1, current2, current3, currentConv, voltage } |
Static Private Attributes | |
static const float | sscale [6] |
The PlaDyPos ROS node for allocation, control and monitoring of the surface platform.
Definition at line 58 of file PlaDyPosNode.hpp.
anonymous enum [private] |
Sensor enumeration.
Definition at line 67 of file PlaDyPosNode.hpp.
Main constructor.
Definition at line 57 of file PlaDyPosNode.cpp.
General destructor.
Definition at line 64 of file PlaDyPosNode.cpp.
void PlaDyPosNode::configure | ( | ros::NodeHandle & | nh, |
ros::NodeHandle & | ph | ||
) |
Definition at line 71 of file PlaDyPosNode.cpp.
void PlaDyPosNode::driverMsg | ( | const int | n[4] | ) | [protected] |
Helper method to generate the driver msg.
Definition at line 228 of file PlaDyPosNode.cpp.
void PlaDyPosNode::dynrec | ( | pladypos::ThrusterMappingConfig & | config, |
uint32_t | level | ||
) | [protected] |
Dynamic reconfigure service.
Definition at line 200 of file PlaDyPosNode.cpp.
void PlaDyPosNode::onReply | ( | const boost::system::error_code & | error, |
const size_t & | transferred | ||
) | [protected] |
Handles the arrived message.
Definition at line 129 of file PlaDyPosNode.cpp.
void PlaDyPosNode::onTau | ( | const auv_msgs::BodyForceReq::ConstPtr | tau | ) | [protected] |
Handles the arrived force and torque requests.
Definition at line 245 of file PlaDyPosNode.cpp.
void PlaDyPosNode::pubDiagnostics | ( | ) | [protected] |
Publishes the diagnostics.
Definition at line 170 of file PlaDyPosNode.cpp.
void PlaDyPosNode::safetyTest | ( | ) | [protected] |
Safety function.
Definition at line 212 of file PlaDyPosNode.cpp.
void PlaDyPosNode::start_receive | ( | ) | [protected] |
Starts the message receive.
Definition at line 123 of file PlaDyPosNode.cpp.
ScaleAllocation labust::vehicles::PlaDyPosNode::allocator [protected] |
The scale allocator.
Definition at line 178 of file PlaDyPosNode.hpp.
Eigen::Matrix<float, 3,4> labust::vehicles::PlaDyPosNode::B [protected] |
Allocation matrix and maximum force, torque.
Definition at line 174 of file PlaDyPosNode.hpp.
ros::Publisher labust::vehicles::PlaDyPosNode::diag [protected] |
Definition at line 89 of file PlaDyPosNode.hpp.
ros::Publisher labust::vehicles::PlaDyPosNode::info [protected] |
Definition at line 89 of file PlaDyPosNode.hpp.
boost::asio::io_service labust::vehicles::PlaDyPosNode::io [protected] |
The asio IO service.
Definition at line 149 of file PlaDyPosNode.hpp.
boost::thread labust::vehicles::PlaDyPosNode::iorunner [protected] |
The io service thread.
Definition at line 157 of file PlaDyPosNode.hpp.
int labust::vehicles::PlaDyPosNode::lastRevs[4] [protected] |
The last revolutions.
Definition at line 169 of file PlaDyPosNode.hpp.
ros::Time labust::vehicles::PlaDyPosNode::lastTau [protected] |
The last TAU.
Definition at line 131 of file PlaDyPosNode.hpp.
boost::asio::serial_port labust::vehicles::PlaDyPosNode::port [protected] |
The pladypos serial port.
Definition at line 153 of file PlaDyPosNode.hpp.
bool labust::vehicles::PlaDyPosNode::revControl [protected] |
The external revolution control flag.
Definition at line 144 of file PlaDyPosNode.hpp.
boost::thread labust::vehicles::PlaDyPosNode::safety [protected] |
The safety test thread.
Definition at line 123 of file PlaDyPosNode.hpp.
boost::asio::streambuf labust::vehicles::PlaDyPosNode::sbuffer [protected] |
The input buffer.
Definition at line 161 of file PlaDyPosNode.hpp.
boost::array<float,6> labust::vehicles::PlaDyPosNode::sensors [protected] |
The sensor measurements
Definition at line 165 of file PlaDyPosNode.hpp.
boost::mutex labust::vehicles::PlaDyPosNode::serialMux [protected] |
The output mutex.
Definition at line 127 of file PlaDyPosNode.hpp.
dynamic_reconfigure::Server<pladypos::ThrusterMappingConfig> labust::vehicles::PlaDyPosNode::server [protected] |
Dynamic reconfigure server.
Definition at line 140 of file PlaDyPosNode.hpp.
const float PlaDyPosNode::sscale [static, private] |
{0.00926, 0.00926, 0.00926, 0.00926, 0.0152738, 0.02795 }
The scaling constants for the driver sensors.
Definition at line 63 of file PlaDyPosNode.hpp.
ros::Subscriber labust::vehicles::PlaDyPosNode::tau [protected] |
The desired force and torque subscriber.
Definition at line 85 of file PlaDyPosNode.hpp.
ros::Publisher labust::vehicles::PlaDyPosNode::tauAch [protected] |
The achieved force and torque publisher.
Definition at line 89 of file PlaDyPosNode.hpp.
double labust::vehicles::PlaDyPosNode::timeout [protected] |
The timeout.
Definition at line 135 of file PlaDyPosNode.hpp.