ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

no match for 'operator-' (operand types are 'ros::Time' and 'ros::Time')

asked 2019-06-18 04:59:23 -0500

Shanika gravatar image

updated 2019-06-19 07:00:18 -0500

Hello,

I am trying to publish odometry following this tutorial from my Arduino but I have the following error:

Firmware_odometry.ino: In function 'void loop()':

Firmware_odometry:458:38: error: no match for 'operator-' (operand types are 'ros::Time' and 'ros::Time')

     dt = (current_time - last_time).toSec();

Here are a few lines of my firmware:

#include <ros.h>
#include <ros/time.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
ros::NodeHandle  nh;
ros::Time current_time, last_time;

geometry_msgs::TransformStamped odom_ts;
geometry_msgs::Quaternion odom_quat; 
tf::TransformBroadcaster odom_bro;
nav_msgs::Odometry odom_msg;

ros::Publisher pub_odom("/odometry",&odom_msg);

long odom_time;
double  xo, yo, tho = 0;
double vx,vth = 0.1;
double vy = -0.1;
double dt, delta_xo, delta_yo, delta_tho;

void setup(){
 nh.initNode();
 nh.advertise(pub_odom);
}

void loop(){
// publish odometry information over ROS
  if(millis() >= odom_time){
  current_time = ros::Time::now();
  last_time = ros::Time::now();

  dt = (current_time - last_time).toSec();
  delta_xo = (vx * cos(tho) - vy * sin(tho)) * dt;
  delta_yo = (vx * sin(tho) + vy * cos(tho)) * dt;
  delta_tho = vth * dt;

  xo += delta_xo;
  yo += delta_yo;
  tho += delta_tho;

//publish the transform over tf
  odom_ts.header.stamp = current_time;
  odom_ts.header.frame_id = "odom";
  odom_ts.child_frame_id = "base_link";
  odom_ts.transform.translation.x = xo;
  odom_ts.transform.translation.y = yo;
  odom_ts.transform.translation.z = 0.0;
  odom_ts.transform.rotation = odom_quat;

//send the transform
  odom_bro.sendTransform(odom_ts);

//publish the odometry message over ROS
  odom_msg.header.stamp = current_time;
  odom_msg.header.frame_id = "odom";

//set the position 
  odom_msg.pose.pose.position.x = xo;
  odom_msg.pose.pose.position.y = yo;
  odom_msg.pose.pose.position.z = 0.0;
  odom_msg.pose.pose.orientation = odom_quat;

//set the velocity
  odom_msg.child_frame_id = "base_link";
  odom_msg.twist.twist.linear.x = vx;
  odom_msg.twist.twist.linear.y = vy;
  odom_msg.twist.twist.angular.z = vth;

  pub_odom.publish(&odom_msg);
  odom_time = millis()+10;
  }
  nh.spinOnce();
  delay(100);
}

Could you please guide me ?

Thanks in advance,

Shanika

edit retag flag offensive close merge delete

Comments

1

rosserial != roscpp. There are differences. On an Arduino you're likely using rosserial, but the tutorial you follow is for roscpp.

gvdhoorn gravatar image gvdhoorn  ( 2019-06-18 05:05:58 -0500 )edit

I see, thank you :)

Shanika gravatar image Shanika  ( 2019-06-18 07:16:31 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-04-03 01:47:36 -0500

mihir3445@gmail.com gravatar image

rosserial does not implement operators and thus the issue.

simpler solution is to replace

dt = (current_time - last_time).toSec();

with

dt = (current_time.toSec() - last_time.toSec());
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-06-18 04:59:23 -0500

Seen: 2,405 times

Last updated: Jun 19 '19