Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #include <hector_pose_estimation/rtt/taskcontext.h>
00030 #include "services.h"
00031 #include "parameters.h"
00032
00033 #include <hector_pose_estimation/system/generic_quaternion_system_model.h>
00034 #include <hector_pose_estimation/measurements/poseupdate.h>
00035 #include <hector_pose_estimation/measurements/height.h>
00036 #include <hector_pose_estimation/measurements/magnetic.h>
00037 #include <hector_pose_estimation/measurements/gps.h>
00038
00039 #include <hector_pose_estimation/ros/parameters.h>
00040
00041 #include <rtt/Component.hpp>
00042
00043 namespace hector_pose_estimation {
00044
00045 PoseEstimationTaskContext::PoseEstimationTaskContext(const std::string& name, const SystemPtr& system)
00046 : RTT::TaskContext(name, RTT::TaskContext::PreOperational)
00047 , PoseEstimation(system)
00048 {
00049 if (!system) addSystem(System::create(new GenericQuaternionSystemModel));
00050
00051 this->addEventPort("raw_imu", imu_input_);
00052 this->addPort("poseupdate", pose_update_input_);
00053 this->addPort("magnetic", magnetic_input_);
00054 this->addPort("pressure_height", height_input_);
00055 this->addPort("fix", gps_input_);
00056 this->addPort("fix_velocity", gps_velocity_input_);
00057 this->addPort("state", state_output_);
00058 this->addPort("imu", imu_output_);
00059 this->addPort("pose", pose_output_);
00060 this->addPort("velocity", velocity_output_);
00061 this->addPort("global", global_position_output_);
00062 this->addPort("angular_velocity_bias", angular_velocity_bias_output_);
00063 this->addPort("linear_acceleration_bias", linear_acceleration_bias_output_);
00064 this->addEventPort("syscommand", command_input_, boost::bind(&PoseEstimationTaskContext::commandCallback, this, _1));
00065
00066 param_namespace_ = "~";
00067 this->addProperty("param_namespace", param_namespace_);
00068
00069 this->addOperation("reset", &PoseEstimationTaskContext::reset, this, RTT::OwnThread);
00070 this->addOperation("getSystemStatus", &PoseEstimation::getSystemStatus, static_cast<PoseEstimation *>(this), RTT::OwnThread);
00071 this->addOperation("getMeasurementStatus", &PoseEstimation::getMeasurementStatus, static_cast<PoseEstimation *>(this), RTT::OwnThread);
00072
00073 PoseEstimation::addMeasurement(new PoseUpdate("PoseUpdate"));
00074 PoseEstimation::addMeasurement(new Height("Height"));
00075 PoseEstimation::addMeasurement(new Magnetic("Magnetic"));
00076 PoseEstimation::addMeasurement(new GPS("GPS"));
00077
00078 for(Systems::iterator it = systems_.begin(); it != systems_.end(); ++it) {
00079 this->provides()->addService(RTT::Service::shared_ptr(new SystemService(this, *it)));
00080 }
00081
00082 for(Measurements::iterator it = measurements_.begin(); it != measurements_.end(); ++it) {
00083 this->provides()->addService(RTT::Service::shared_ptr(new MeasurementService(this, *it)));
00084 }
00085
00086 PoseEstimation::parameters().initialize(ParameterRegistryROS(ros::NodeHandle(param_namespace_)));
00087 PoseEstimation::parameters().initialize(ParameterRegistryProperties(this->properties()));
00088 }
00089
00090 PoseEstimationTaskContext::~PoseEstimationTaskContext()
00091 {
00092 stop();
00093 cleanup();
00094 }
00095
00096 bool PoseEstimationTaskContext::configureHook()
00097 {
00098 if (!PoseEstimation::init()) {
00099 RTT::log(RTT::Error) << "Intitialization of pose estimation failed!" << RTT::endlog();
00100 return false;
00101 }
00102
00103
00104 updateOutputs();
00105
00106 return true;
00107 }
00108
00109 void PoseEstimationTaskContext::cleanupHook()
00110 {
00111 PoseEstimation::cleanup();
00112 }
00113
00114 bool PoseEstimationTaskContext::startHook()
00115 {
00116 return true;
00117 }
00118
00119 void PoseEstimationTaskContext::stopHook()
00120 {
00121 }
00122
00123 void PoseEstimationTaskContext::updateHook()
00124 {
00125 while(magnetic_input_.read(magnetic_) == RTT::NewData && PoseEstimation::getMeasurement("Magnetic"))
00126 {
00127 Magnetic::MeasurementVector update(3);
00128 update.x() = magnetic_.vector.x;
00129 update.y() = magnetic_.vector.y;
00130 update.z() = magnetic_.vector.z;
00131 PoseEstimation::getMeasurement("Magnetic")->add(Magnetic::Update(update));
00132 }
00133
00134 while(height_input_.read(height_) == RTT::NewData && PoseEstimation::getMeasurement("Height"))
00135 {
00136 Height::Update update;
00137 #ifdef USE_MAV_MSGS
00138 update = height_.height;
00139 #else
00140 update = height_.point.z;
00141 #endif
00142 PoseEstimation::getMeasurement("Height")->add(update);
00143 }
00144
00145 while(gps_input_.read(gps_) == RTT::NewData && gps_velocity_input_.read(gps_velocity_) != RTT::NoData && PoseEstimation::getMeasurement("GPS"))
00146 {
00147 if (gps_.status.status != sensor_msgs::NavSatStatus::STATUS_NO_FIX)
00148 {
00149 GPS::Update update;
00150 update.latitude = gps_.latitude * M_PI/180.0;
00151 update.longitude = gps_.longitude * M_PI/180.0;
00152 update.velocity_north = gps_velocity_.vector.x;
00153 update.velocity_east = -gps_velocity_.vector.y;
00154 PoseEstimation::getMeasurement("GPS")->add(update);
00155 }
00156 }
00157
00158 while(pose_update_input_.read(pose_update_) == RTT::NewData && PoseEstimation::getMeasurement("PoseUpdate"))
00159 {
00160 PoseEstimation::getMeasurement("PoseUpdate")->add(PoseUpdate::Update(pose_update_));
00161 }
00162
00163 while(imu_input_.read(imu_in_) == RTT::NewData) {
00164 setInput(ImuInput(imu_in_));
00165 PoseEstimation::update(imu_in_.header.stamp);
00166 updateOutputs();
00167 }
00168 }
00169
00170 void PoseEstimationTaskContext::updateOutputs()
00171 {
00172 getState(state_);
00173 state_output_.write(state_);
00174
00175 if (imu_output_.connected()) {
00176 imu_out_.header = state_.header;
00177 imu_out_.orientation = state_.pose.pose.orientation;
00178 getImuWithBiases(imu_out_.linear_acceleration, imu_out_.angular_velocity);
00179 imu_output_.write(imu_out_);
00180 }
00181
00182 if (pose_output_.connected()) {
00183 pose_.header = state_.header;
00184 pose_.pose = state_.pose.pose;
00185 pose_output_.write(pose_);
00186 }
00187
00188 if (velocity_output_.connected()) {
00189 velocity_.header = state_.header;
00190 velocity_.vector = state_.twist.twist.linear;
00191 velocity_output_.write(velocity_);
00192 }
00193
00194 if (global_position_output_.connected()) {
00195 getGlobalPosition(global_position_);
00196 global_position_output_.write(global_position_);
00197 }
00198
00199 if (angular_velocity_bias_output_.connected() || linear_acceleration_bias_output_.connected()) {
00200 getHeader(angular_velocity_bias_.header);
00201 getHeader(linear_acceleration_bias_.header);
00202 getBias(angular_velocity_bias_, linear_acceleration_bias_);
00203 angular_velocity_bias_output_.write(angular_velocity_bias_);
00204 linear_acceleration_bias_output_.write(linear_acceleration_bias_);
00205 }
00206 }
00207
00208
00209 void PoseEstimationTaskContext::reset() {
00210 RTT::log(RTT::Info) << "Resetting pose_estimation" << RTT::endlog();
00211 PoseEstimation::reset();
00212 updateOutputs();
00213 }
00214
00215 void PoseEstimationTaskContext::commandCallback(RTT::base::PortInterface *) {
00216 std_msgs::String command;
00217 if (command_input_.read(command) == RTT::NewData) {
00218 if (command.data == "reset") reset();
00219 }
00220 }
00221
00222 }
00223
00224 ORO_CREATE_COMPONENT( hector_pose_estimation::PoseEstimationTaskContext )