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

Added support for publishing raw wheel encoder ticks #11

Open
wants to merge 1 commit into
base: indigo-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
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
9 changes: 9 additions & 0 deletions include/husky_base/husky_hardware.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
#include "ros/ros.h"
#include "sensor_msgs/JointState.h"
#include "husky_msgs/HuskyStatus.h"
#include "husky_msgs/HuskyWheelTick.h"

#include <string>

namespace husky_base
Expand All @@ -54,6 +56,7 @@ namespace husky_base
HuskyHardware(ros::NodeHandle nh, ros::NodeHandle private_nh);

void updateJointsFromHardware();
void updateWheelTicksFromHardware();

void writeCommandsToHardware();

Expand Down Expand Up @@ -86,11 +89,17 @@ namespace husky_base
ros::Publisher diagnostic_publisher_;
husky_msgs::HuskyStatus husky_status_msg_;
diagnostic_updater::Updater diagnostic_updater_;

HuskyHardwareDiagnosticTask<clearpath::DataSystemStatus> system_status_task_;
HuskyHardwareDiagnosticTask<clearpath::DataPowerSystem> power_status_task_;
HuskyHardwareDiagnosticTask<clearpath::DataSafetySystemStatus> safety_status_task_;
HuskySoftwareDiagnosticTask software_status_task_;

//Wheel tick support
ros::Publisher wheel_publisher_;
husky_msgs::HuskyWheelTick husky_wheel_msg_;
void initializeWheelTicks();

// ROS Parameters
double wheel_diameter_, max_accel_, max_speed_;

Expand Down
2 changes: 2 additions & 0 deletions src/husky_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ void controlLoop(const ros::TimerEvent &event, husky_base::HuskyHardware &husky,
{
husky.reportLoopFrequency(event);
husky.updateJointsFromHardware();
husky.updateWheelTicksFromHardware();

cm.update(event.current_real, event.current_real - event.last_real);
husky.writeCommandsToHardware();
}
Expand Down
31 changes: 31 additions & 0 deletions src/husky_hardware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ namespace husky_base
connect(port);
resetTravelOffset();
initializeDiagnostics();
initializeWheelTicks();
registerControlInterfaces();
}

Expand Down Expand Up @@ -128,6 +129,10 @@ namespace husky_base
diagnostic_publisher_ = nh_.advertise<husky_msgs::HuskyStatus>("status", 10);
}

void HuskyHardware::initializeWheelTicks()
{
wheel_publisher_ = nh_.advertise<husky_msgs::HuskyWheelTick>("wheel_tick", 10);
}

/**
* Register interfaces with the RobotHW interface manager, allowing ros_control operation
Expand Down Expand Up @@ -160,11 +165,37 @@ namespace husky_base
diagnostic_publisher_.publish(husky_status_msg_);
}

/*Update the wheel ticks and publish */
void HuskyHardware::updateWheelTicksFromHardware()
{
Msg<clearpath::DataEncodersRaw>::Ptr enc = Msg<clearpath::DataEncodersRaw>::getUpdate();

int index = 0;
if (enc)
{
husky_wheel_msg_.name.clear();
husky_wheel_msg_.tickCount.clear();

//ROS_INFO("Found %d encoders", enc->getCount());
husky_wheel_msg_.name.push_back("left");
husky_wheel_msg_.tickCount.push_back(enc->getTicks(index));

index++;
husky_wheel_msg_.name.push_back("right");
husky_wheel_msg_.tickCount.push_back(enc->getTicks(index));

husky_wheel_msg_.header.stamp = ros::Time::now();
wheel_publisher_.publish(husky_wheel_msg_);
}
}

/**
* Pull latest speed and travel measurements from MCU, and store in joint structure for ros_control
*/
void HuskyHardware::updateJointsFromHardware()
{


Msg<clearpath::DataEncoders>::Ptr enc = Msg<clearpath::DataEncoders>::getUpdate();
if (enc)
{
Expand Down