Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove debug topics #25

Merged
merged 2 commits into from
May 6, 2017
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
21 changes: 0 additions & 21 deletions include/ubiquity_motor/motor_hardware.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,27 +89,6 @@ class MotorHardware : public hardware_interface::RobotHW {
ros::Publisher leftError;
ros::Publisher rightError;

ros::Publisher pubU50;
ros::Publisher pubS50;
ros::Publisher pubU51;
ros::Publisher pubS51;
ros::Publisher pubU52;
ros::Publisher pubS52;
ros::Publisher pubU53;
ros::Publisher pubS53;
ros::Publisher pubU54;
ros::Publisher pubS54;
ros::Publisher pubU55;
ros::Publisher pubS55;
ros::Publisher pubU56;
ros::Publisher pubS56;
ros::Publisher pubU57;
ros::Publisher pubS57;
ros::Publisher pubU58;
ros::Publisher pubS58;
ros::Publisher pubU59;
ros::Publisher pubS59;

MotorSerial* motor_serial_;

FRIEND_TEST(MotorHardwareTests, nonZeroWriteSpeedsOutputs);
Expand Down
69 changes: 2 additions & 67 deletions src/motor_hardware.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,27 +68,6 @@ MotorHardware::MotorHardware(ros::NodeHandle nh, CommsParams serial_params,
leftError = nh.advertise<std_msgs::Int32>("left_error", 1);
rightError = nh.advertise<std_msgs::Int32>("right_error", 1);

pubU50 = nh.advertise<std_msgs::UInt32>("u50", 1);
pubS50 = nh.advertise<std_msgs::Int32>("s50", 1);
pubU51 = nh.advertise<std_msgs::UInt32>("u51", 1);
pubS51 = nh.advertise<std_msgs::Int32>("s51", 1);
pubU52 = nh.advertise<std_msgs::UInt32>("u52", 1);
pubS52 = nh.advertise<std_msgs::Int32>("s52", 1);
pubU53 = nh.advertise<std_msgs::UInt32>("u53", 1);
pubS53 = nh.advertise<std_msgs::Int32>("s53", 1);
pubU54 = nh.advertise<std_msgs::UInt32>("u54", 1);
pubS54 = nh.advertise<std_msgs::Int32>("s54", 1);
pubU55 = nh.advertise<std_msgs::UInt32>("u55", 1);
pubS55 = nh.advertise<std_msgs::Int32>("s55", 1);
pubU56 = nh.advertise<std_msgs::UInt32>("u56", 1);
pubS56 = nh.advertise<std_msgs::Int32>("s56", 1);
pubU57 = nh.advertise<std_msgs::UInt32>("u57", 1);
pubS57 = nh.advertise<std_msgs::Int32>("s57", 1);
pubU58 = nh.advertise<std_msgs::UInt32>("u58", 1);
pubS58 = nh.advertise<std_msgs::Int32>("s58", 1);
pubU59 = nh.advertise<std_msgs::UInt32>("u59", 1);
pubS59 = nh.advertise<std_msgs::Int32>("s59", 1);

sendPid_count = 0;

pid_params = firmware_params;
Expand Down Expand Up @@ -164,50 +143,7 @@ void MotorHardware::readInputs() {
break;
}
default:
uint8_t reg = mm.getRegister();
int32_t data = mm.getData();
std_msgs::UInt32 umsg;
std_msgs::Int32 smsg;
umsg.data = data;
smsg.data = data;
switch (reg) {
case 0x50:
pubU50.publish(umsg);
pubS50.publish(smsg);
break;
case 0x51:
pubU51.publish(umsg);
pubS51.publish(smsg);
break;
case 0x52:
pubU52.publish(umsg);
pubS52.publish(smsg);
break;
case 0x53:
pubU53.publish(umsg);
pubS53.publish(smsg);
break;
case 0x54:
pubU54.publish(umsg);
pubS54.publish(smsg);
break;
case 0x55:
pubU55.publish(umsg);
pubS55.publish(smsg);
break;
case 0x56:
pubU56.publish(umsg);
pubS56.publish(smsg);
break;
case 0x57:
pubU57.publish(umsg);
pubS57.publish(smsg);
break;
case 0x58:
pubU58.publish(umsg);
pubS58.publish(smsg);
break;
}
break;
}
}
}
Expand All @@ -226,7 +162,6 @@ void MotorHardware::writeSpeeds() {

std_msgs::Int32 smsg;
smsg.data = left_tics;
pubS59.publish(smsg);

motor_serial_->transmitCommand(both);

Expand Down Expand Up @@ -363,4 +298,4 @@ int16_t MotorHardware::calculateTicsFromRadians(double radians) const {

double MotorHardware::calculateRadiansFromTics(int16_t tics) const {
return (tics * VELOCITY_READ_PER_SECOND / QTICS_PER_RADIAN);
}
}