mirror of
https://github.com/6-robot/wpb_home.git
synced 2025-09-15 12:58:59 +08:00
add odom flag
This commit is contained in:
parent
7219148a97
commit
92cfe78b0e
@ -2,7 +2,8 @@
|
||||
|
||||
<!-- wpb_home core-->
|
||||
<node pkg="wpb_home_bringup" type="wpb_home_core" name="wpb_home_core" output="screen">
|
||||
<param name="serial_port" type="string" value="/dev/ftdi"/>
|
||||
<param name="serial_port" type="string" value="/dev/ftdi"/>
|
||||
<param name="odom" type="bool" value="false"/>
|
||||
<rosparam file="$(find wpb_home_bringup)/config/wpb_home.yaml" command="load" />
|
||||
</node>
|
||||
|
||||
|
||||
@ -145,8 +145,11 @@ int main(int argc, char** argv)
|
||||
n_param.param<std::string>("serial_port", strSerialPort, "/dev/ttyUSB0");
|
||||
m_wpb_home.Open(strSerialPort.c_str(),115200);
|
||||
|
||||
bool bImuOdom;
|
||||
bool bImuOdom = false;
|
||||
n_param.param<bool>("imu_odom", bImuOdom, false);
|
||||
|
||||
bool bOdom = true;
|
||||
n_param.param<bool>("odom", bOdom, true);
|
||||
|
||||
ros::Time current_time, last_time;
|
||||
current_time = ros::Time::now();
|
||||
@ -279,9 +282,12 @@ int main(int argc, char** argv)
|
||||
odom.twist.twist.angular.y = 0;
|
||||
odom.twist.twist.angular.z = fVz;
|
||||
|
||||
//plublishing the odometry and new tf
|
||||
broadcaster.sendTransform(odom_trans);
|
||||
odom_pub.publish(odom);
|
||||
if(bOdom == true)
|
||||
{
|
||||
//plublishing the odometry and new tf
|
||||
broadcaster.sendTransform(odom_trans);
|
||||
odom_pub.publish(odom);
|
||||
}
|
||||
|
||||
lastVel.linear.x = fVx;
|
||||
lastVel.linear.y = fVy;
|
||||
@ -293,12 +299,15 @@ int main(int argc, char** argv)
|
||||
}
|
||||
else
|
||||
{
|
||||
odom_trans.header.stamp = ros::Time::now();
|
||||
//plublishing the odometry and new tf
|
||||
broadcaster.sendTransform(odom_trans);
|
||||
odom.header.stamp = ros::Time::now();
|
||||
odom_pub.publish(odom);
|
||||
//ROS_INFO("[odom] zero");
|
||||
if(bOdom == true)
|
||||
{
|
||||
odom_trans.header.stamp = ros::Time::now();
|
||||
//plublishing the odometry and new tf
|
||||
broadcaster.sendTransform(odom_trans);
|
||||
odom.header.stamp = ros::Time::now();
|
||||
odom_pub.publish(odom);
|
||||
//ROS_INFO("[odom] zero");
|
||||
}
|
||||
}
|
||||
|
||||
pose_diff_pub.publish(pose_diff_msg);
|
||||
|
||||
Loading…
Reference in New Issue
Block a user