HebiGroup is a collection of one or more modules.
Groups of modules are the basic way to send commands and retrieve
feedback. They provide convenient ways to deal with modules, and
handle high-level issues such as data synchronization and logging.
HebiGroup Methods (configuration):
getNumModules - returns the number of grouped modules
setFeedbackFrequency - sets the feedback request rate
getFeedbackFrequency - gets the feedback request rate
setCommandLifetime - sets the command lifetime
getCommandLifetime - gets the command lifetime
HebiGroup Methods (common):
send - sends synchronized commands, as well as a
number of other settings and parameters
getNextFeedback - returns the next new 'simple' feedback
getNextFeedbackFull - returns the next new 'full' feedback
getNextFeedbackIO - returns the next new 'I/O' board feedback
getNextFeedbackMobile - returns the next new 'mobile' feedback
getInfo - returns meta information such as names
getGains - returns the current gains
getSafetyParams - returns safety parameters such as limits
setLocalState - sets local user state for logging purposes
getLocalState - returns the most recently set local state
startLog - starts background logging to disk
isLogging - returns whether logging is currently active
stopLog - stops logging and returns a readable format
stopLogFull - same as above, returning full feedback
stopLogIO - same as above, returning I/O feedback
stopLogMobile - same as above, returning mobile feedback
Example
% 200 Hz loop commanding of the current position
group.setFeedbackFrequency(200);
cmd = CommandStruct();
group.startLog();
t0 = tic();
while toc(t0) < 5
fbk = group.getNextFeedback();
cmd.position = fbk.position;
group.send(cmd);
end
log = group.stopLog();
% Plotting the commanded / feedback positions
plot(log.time, log.position);
hold on;
plot(log.time, log.positionCmd, '--');
hold off;
xlabel('time (sec)');
ylabel('position (rad)');
legend(group.getInfo.name);