Skip to content

Commit

Permalink
migrates rflex, old message API deprecated
Browse files Browse the repository at this point in the history
  • Loading branch information
Mikhail Medvedev committed Sep 11, 2012
1 parent 629ff91 commit 888cbcd
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 8 deletions.
5 changes: 3 additions & 2 deletions atrvjr_drivers/rflex/src/atrvjr_driver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <rflex/atrvjr_driver.h>
#include <rflex/atrvjr_config.h>
#include <math.h>
#include <cstdio>

ATRVJR::ATRVJR() {
found_distance = false;
Expand Down Expand Up @@ -154,7 +155,7 @@ void ATRVJR::getSonarPoints(const int ringi, sensor_msgs::PointCloud* cloud) con
int numSonar = SONARS_PER_RING[ringi];
float* readings = new float[numSonar];
getSonarReadings(ringi, readings);
cloud->set_points_size(numSonar);
cloud->points.resize(numSonar);
int c = 0;
for (int i = 0; i < numSonar; ++i) {
if (readings[i] < SONAR_MAX_RANGE/ (float) RANGE_CONVERSION) {
Expand Down Expand Up @@ -185,7 +186,7 @@ int ATRVJR::getBumps(const int index, sensor_msgs::PointCloud* cloud) const {
}
}

cloud->set_points_size(total);
cloud->points.resize(total);
if (total==0)
return 0;
for (int i=0;i<BUMPERS_PER[index];i++) {
Expand Down
4 changes: 2 additions & 2 deletions atrvjr_drivers/rflex/src/atrvjr_node.cc
Original file line number Diff line number Diff line change
Expand Up @@ -254,8 +254,8 @@ void ATRVJRNode::publishOdometry() {
// finally, publish the joint state
sensor_msgs::JointState joint_state;
joint_state.header.stamp = ros::Time::now();
joint_state.set_name_size(1);
joint_state.set_position_size(1);
joint_state.name.resize(1);
joint_state.position.resize(1);
joint_state.name[0] = "lewis_twist";
joint_state.position[0] = true_bearing;

Expand Down
5 changes: 3 additions & 2 deletions atrvjr_drivers/rflex/src/b21_driver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <rflex/b21_driver.h>
#include <rflex/b21_config.h>
#include <math.h>
#include <cstdio>

B21::B21() {
found_distance = false;
Expand Down Expand Up @@ -153,7 +154,7 @@ void B21::getSonarPoints(const int ringi, sensor_msgs::PointCloud* cloud) const
int numSonar = SONARS_PER_RING[ringi];
float* readings = new float[numSonar];
getSonarReadings(ringi, readings);
cloud->set_points_size(numSonar);
cloud->points.resize(numSonar);
int c = 0;
for (int i = 0; i < numSonar; ++i) {
if (readings[i] < SONAR_MAX_RANGE/ (float) RANGE_CONVERSION) {
Expand Down Expand Up @@ -184,7 +185,7 @@ int B21::getBumps(const int index, sensor_msgs::PointCloud* cloud) const {
}
}

cloud->set_points_size(total);
cloud->points.resize(total);
if (total==0)
return 0;
for (int i=0;i<BUMPERS_PER[index];i++) {
Expand Down
5 changes: 3 additions & 2 deletions atrvjr_drivers/rflex/src/b21_node.cc
Original file line number Diff line number Diff line change
Expand Up @@ -264,8 +264,9 @@ void B21Node::publishOdometry() {
// finally, publish the joint state
sensor_msgs::JointState joint_state;
joint_state.header.stamp = ros::Time::now();
joint_state.set_name_size(1);
joint_state.set_position_size(1);

joint_state.name.resize(1);
joint_state.position.resize(1);
joint_state.name[0] = "lewis_twist";
joint_state.position[0] = true_bearing;

Expand Down

0 comments on commit 888cbcd

Please sign in to comment.