Go to the documentation of this file.00001 #include "darwin_odom_alg_node.h"
00002
00003 DarwinOdomAlgNode::DarwinOdomAlgNode(void) :
00004 algorithm_base::IriBaseAlgorithm<DarwinOdomAlgorithm>()
00005 {
00006
00007 this->loop_rate_ = 100;
00008
00009 this->public_node_handle_.param<std::string>("tf_prefix", this->tf_prefix_, "");
00010 this->public_node_handle_.param<std::string>("odom_id", this->odom_id_, "odom" );
00011 this->public_node_handle_.param<std::string>("base_link_id", this->base_link_id_, "base_link" );
00012 this->public_node_handle_.param<bool> ("publish_tf", this->publish_tf_, true );
00013
00014
00015 if( this->tf_prefix_.size()!=0 )
00016 {
00017 this->odom_id_ = this->tf_prefix_ + "/" + this->odom_id_;
00018 this->base_link_id_ = this->tf_prefix_ + "/" + this->base_link_id_;
00019 }
00020
00021
00022 this->odom_publisher_ = this->public_node_handle_.advertise<nav_msgs::Odometry>("odom", 100);
00023
00024
00025 this->darwin_imu_subscriber_ = this->public_node_handle_.subscribe("darwin_imu", 100, &DarwinOdomAlgNode::darwin_imu_callback, this);
00026
00027
00028
00029
00030
00031
00032
00033
00034 }
00035
00036 DarwinOdomAlgNode::~DarwinOdomAlgNode(void)
00037 {
00038
00039 }
00040
00041 void DarwinOdomAlgNode::mainNodeThread(void)
00042 {
00043 ros::Time current_time = ros::Time::now();
00044 geometry_msgs::TransformStamped odom_trans_msg;
00045 static ros::Time last_time = ros::Time::now();
00046 static double yaw_angle=0.0,pitch_angle=0.0,roll_angle=0.0;
00047
00048 double dt = (current_time - last_time).toSec();
00049
00050
00051 this->darwin_imu_mutex_.enter();
00052 yaw_angle+=this->status.angular_velocity.z*dt;
00053 pitch_angle+=this->status.angular_velocity.y*dt;
00054 roll_angle+=this->status.angular_velocity.x*dt;
00055
00056
00057 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromRollPitchYaw(roll_angle,pitch_angle,yaw_angle);
00058
00059
00060 transform_.translation.x += twist_.twist.linear.x*dt;
00061 transform_.translation.y += twist_.twist.linear.y*dt;
00062 transform_.translation.z += twist_.twist.linear.z*dt;
00063 transform_.rotation = odom_quat;
00064
00065
00066 pose_.pose.position.x += twist_.twist.linear.x*dt;
00067 pose_.pose.position.y += twist_.twist.linear.y*dt;
00068 pose_.pose.position.z += twist_.twist.linear.z*dt;
00069 pose_.pose.orientation = odom_quat;
00070
00071
00072 twist_.twist.linear.x += this->status.linear_acceleration.x*dt;
00073 twist_.twist.linear.y += this->status.linear_acceleration.y*dt;
00074 twist_.twist.linear.z += this->status.linear_acceleration.z*dt;
00075 twist_.twist.angular.x = this->status.angular_velocity.x;
00076 twist_.twist.angular.y = this->status.angular_velocity.y;
00077 twist_.twist.angular.z = this->status.angular_velocity.z;
00078 this->darwin_imu_mutex_.exit();
00079
00080
00081 last_time = current_time;
00082
00083
00084 if(this->publish_tf_)
00085 {
00086
00087 odom_trans_msg.header.stamp = current_time;
00088 odom_trans_msg.header.frame_id = this->odom_id_;
00089 odom_trans_msg.child_frame_id = this->base_link_id_;
00090 odom_trans_msg.transform = this->transform_;
00091
00092 this->odom_broadcaster_.sendTransform(odom_trans_msg);
00093 }
00094
00095
00096 this->Odometry_msg_.header.stamp = current_time;
00097 this->Odometry_msg_.header.frame_id = this->odom_id_;
00098 this->Odometry_msg_.child_frame_id = this->base_link_id_;
00099 this->Odometry_msg_.pose = this->pose_;
00100 this->Odometry_msg_.twist = this->twist_;
00101
00102
00103 this->odom_publisher_.publish(this->Odometry_msg_);
00104
00105
00106
00107
00108
00109
00110
00111 }
00112
00113
00114 void DarwinOdomAlgNode::darwin_imu_callback(const sensor_msgs::Imu::ConstPtr& msg)
00115 {
00116 ROS_INFO("DarwinOdomAlgNode::darwin_imu_callback: New Message Received");
00117
00118
00119
00120 this->darwin_imu_mutex_.enter();
00121
00122
00123 this->status=*msg;
00124
00125
00126
00127 this->darwin_imu_mutex_.exit();
00128 }
00129
00130
00131
00132
00133
00134
00135
00136 void DarwinOdomAlgNode::node_config_update(Config &config, uint32_t level)
00137 {
00138 this->alg_.lock();
00139
00140 this->alg_.unlock();
00141 }
00142
00143 void DarwinOdomAlgNode::addNodeDiagnostics(void)
00144 {
00145 }
00146
00147
00148 int main(int argc,char *argv[])
00149 {
00150 return algorithm_base::main<DarwinOdomAlgNode>(argc, argv, "darwin_odom_alg_node");
00151 }