#include <labust/xml/XMLReader.hpp>
#include <labust/simulation/VehicleModel6DOF.hpp>
#include <labust/vehicles/ScaleAllocation.hpp>
#include <labust/tools/rosutils.hpp>
#include <labust/tools/GeoUtilities.hpp>
#include <auv_msgs/NavSts.h>
#include <auv_msgs/BodyForceReq.h>
#include <nav_msgs/Odometry.h>
#include <std_msgs/String.h>
#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/FluidPressure.h>
#include <geometry_msgs/TwistStamped.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <ros/ros.h>
#include <Eigen/Dense>
#include <boost/bind.hpp>
#include <sstream>
#include <string>
Go to the source code of this file.
Functions |
void | handleCurrent (labust::simulation::vector *current, const std_msgs::String::ConstPtr &data) |
void | handleTau (labust::simulation::vector *tauIn, const auv_msgs::BodyForceReq::ConstPtr &tau) |
int | main (int argc, char *argv[]) |
geometry_msgs::TwistStamped * | mapToDvl (const labust::simulation::vector &eta, const labust::simulation::vector &nu, geometry_msgs::TwistStamped *dvl, tf::TransformBroadcaster &dvlBroadcast) |
sensor_msgs::Imu * | mapToImu (const labust::simulation::vector &eta, const labust::simulation::vector &nu, const labust::simulation::vector &nuacc, sensor_msgs::Imu *imu, tf::TransformBroadcaster &imuBroadcast) |
sensor_msgs::NavSatFix * | mapToNavSatFix (const labust::simulation::vector &eta, const labust::simulation::vector &nu, sensor_msgs::NavSatFix *fix, const std::string &utmzone, tf::TransformListener &lisWorld, tf::TransformBroadcaster &gpsBroadcast) |
auv_msgs::NavSts * | mapToNavSts (const labust::simulation::vector &eta, const labust::simulation::vector &nu, auv_msgs::NavSts *nav) |
nav_msgs::Odometry * | mapToUWSimOdometry (const labust::simulation::vector &eta, const labust::simulation::vector &nu, nav_msgs::Odometry *odom, tf::TransformListener &lisWorld) |
double | modelLat (0) |
double | modelLon (0) |
double | originLat (0) |
double | originLon (0) |
double | thrustScale (1) |
Function Documentation
int main |
( |
int |
argc, |
|
|
char * |
argv[] |
|
) |
| |