Publisher Subscriber not working
Hi everyone,
I have been using ROS for quite a while but am suddenly stuck with a very weird problem. In a part of my code, the subscriber to a publisher is not working within the code segment. If I try to use rostopic echo, it works fine but as soon as I try running the subscriber node, not only does it give no result but also after disconnecting the subscriber node if I try to perform rostopic echo it does not work anymore. This is a very strange problem and any help would be very much appreciated. I am attaching the subscriber publisher nodes (much simplified versions)
#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <visualization_msgs/Marker.h>
#include <std_msgs/String.h>
#include <sensor_msgs/LaserScan.h>
#include <nav_msgs/Odometry.h>
#include <fstream>
#include <sstream>
#include <string>
#include <stdlib.h>
#include <algorithm>
#include <cstdlib>
#include <vector>
#include <math.h>
#include <std_msgs/MultiArrayLayout.h>
#include <std_msgs/MultiArrayDimension.h>
#include <std_msgs/Float32MultiArray.h>
#include <std_msgs/Int8.h>
#include "list_velocity_tracking.h"
#define PI 3.14159265
using namespace std;
std_msgs::Int8 lane_indicator;
void laneCallback(const std_msgs::Int8::ConstPtr& lc);
int main(int argc, char** argv)
{
ros::init(argc, argv, "velocit_estimation_list");
ros::NodeHandle n;
ros::NodeHandle n1;
pub2 = n.advertise<std_msgs::Int8>("lane_change_indicator", 5);
int count = 0;
lane_indicator.data = 0;
while(ros::ok())
{
pub2.publish(lane_indicator);
}
}
and the subscriber node
#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <visualization_msgs/Marker.h>
#include <std_msgs/String.h>
#include <sensor_msgs/LaserScan.h>
#include <nav_msgs/Odometry.h>
#include <fstream>
#include <sstream>
#include <string>
#include <stdlib.h>
#include <algorithm>
#include <cstdlib>
#include <vector>
#include <math.h>
#include <std_msgs/MultiArrayLayout.h>
#include <std_msgs/MultiArrayDimension.h>
#include <std_msgs/Float32MultiArray.h>
#include <std_msgs/Int8.h>
#include "list_velocity_tracking.h"
#define PI 3.14159265
using namespace std;
void laneCallback(const std_msgs::Int8::ConstPtr& lc);
int main(int argc, char** argv)
{
ros::init(argc, argv, "velocit_estimation_list");
ros::NodeHandle n;
ros::NodeHandle n1;
lane_lock = n.subscribe("lane_change_indicator", 10, laneCallback);
int count = 0;
while(ros::ok())
{
ros::spinOnce();
}
}
void laneCallback(const std_msgs::Int8::ConstPtr& lc)
{
cout<<"inside callback\n";
}
and yes, I have included lane_lock in the header file as a ROS subscriber. thanks a lot in advance