46 dynamic_reconfigure::Server<sick_tim::SickTimConfig>::CallbackType
f;
61 sensor_msgs::LaserScan scan_msg;
63 std::vector<char> str(datagram_msg->data.begin(), datagram_msg->data.end());
70 ROS_ERROR(
"parse_datagram returned %d!", success);
75 if (conf.min_ang > conf.max_ang)
77 ROS_WARN(
"Minimum angle must be greater than maximum angle. Adjusting min_ang.");
78 conf.min_ang = conf.max_ang;
90 int main(
int argc,
char **argv)
92 ros::init(argc, argv,
"sick_tim_datagram_test");
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual int parse_datagram(char *datagram, size_t datagram_length, SickTimConfig &config, sensor_msgs::LaserScan &msg)=0
dynamic_reconfigure::Server< sick_tim::SickTimConfig > dynamic_reconfigure_server_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
SickTimDatagramTest(AbstractParser *parser)
ROSCPP_DECL void spin(Spinner &spinner)
virtual ~SickTimDatagramTest()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void check_angle_range(SickTimConfig &conf)
void datagramCB(const std_msgs::String::ConstPtr &msg)
void update_config(sick_tim::SickTimConfig &new_config, uint32_t level=0)