Public Member Functions | Private Attributes
Romeo Class Reference

#include <romeo.h>

Inheritance diagram for Romeo:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void brokerDisconnected (const string &event_name, const string &broker_name, const string &subscriber_identifier)
void commandVelocity (const geometry_msgs::TwistConstPtr &msg)
bool connect (const ros::NodeHandle nh)
bool connected ()
void controllerLoop ()
void DCMAliasTimedCommand (const string &alias, const vector< float > &values, const vector< int > &timeOffsets, const string &type="Merge", const string &type2="time-mixed")
void DCMTimedCommand (const string &key, const AL::ALValue &value, const int &timeOffset, const string &type="Merge")
void declareEvent (const string &name)
void disconnect ()
AL::ALValue getDataFromMemory (const string &key)
void highCommunicationLoop ()
bool initialize ()
bool initializeControllers (controller_manager::ControllerManager &cm)
void insertDataToMemory (const string &key, const AL::ALValue &value)
void loadParams ()
void lowCommunicationLoop ()
void publishJointStateFromAlMotion ()
void raiseEvent (const string &name, const AL::ALValue &value)
void raiseMicroEvent (const string &name, const AL::ALValue &value)
void readJoints ()
 Romeo (boost::shared_ptr< AL::ALBroker > broker, const std::string &name)
void run ()
void subscribe ()
void subscribeToEvent (const std::string &name, const std::string &callback_module, const std::string &callback_method)
void subscribeToMicroEvent (const std::string &name, const std::string &callback_module, const std::string &callback_method, const string &callback_message="")
bool switchStiffnesses (romeo_dcm_msgs::BoolService::Request &req, romeo_dcm_msgs::BoolService::Response &res)
void unsubscribeFromEvent (const string &name, const string &callback_module)
void unsubscribeFromMicroEvent (const string &name, const string &callback_module)
void writeJoints ()
 ~Romeo ()

Private Attributes

string body_type_
ros::Subscriber cmd_vel_sub_
AL::ALValue commands_
double controller_freq_
boost::shared_ptr< AL::ALProxy > dcm_proxy_
diagnostic_updater::Updater diagnostic_
double high_freq_
bool is_connected_
hardware_interface::PositionJointInterface jnt_pos_interface_
hardware_interface::JointStateInterface jnt_state_interface_
vector< double > joint_angles_
vector< double > joint_commands_
vector< double > joint_efforts_
vector< string > joint_names_
double joint_precision_
vector< double > joint_velocities_
vector< string > joints_names_
double low_freq_
sensor_msgs::JointState m_jointState
ros::Publisher m_jointStatePub
boost::shared_ptr
< AL::ALMotionProxy > 
m_motionProxy
controller_manager::ControllerManagermanager_
AL::ALMemoryProxy memory_proxy_
ros::NodeHandle node_handle_
int number_of_joints_
string odom_frame_
string prefix_
std_msgs::Float32 stiffness_
ros::Publisher stiffness_pub_
ros::ServiceServer stiffness_switch_
bool stiffnesses_enabled_
int topic_queue_
string version_

Detailed Description

Definition at line 82 of file romeo.h.


Constructor & Destructor Documentation

Romeo::Romeo ( boost::shared_ptr< AL::ALBroker >  broker,
const std::string &  name 
)

Copyright (c) 2014, Konstantinos Chatzilygeroudis All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Definition at line 32 of file romeo.cpp.

Definition at line 41 of file romeo.cpp.


Member Function Documentation

void Romeo::brokerDisconnected ( const string &  event_name,
const string &  broker_name,
const string &  subscriber_identifier 
)

Definition at line 299 of file romeo.cpp.

void Romeo::commandVelocity ( const geometry_msgs::TwistConstPtr &  msg)

Definition at line 555 of file romeo.cpp.

bool Romeo::connect ( const ros::NodeHandle  nh)

Definition at line 182 of file romeo.cpp.

bool Romeo::connected ( )

Definition at line 550 of file romeo.cpp.

Definition at line 512 of file romeo.cpp.

void Romeo::DCMAliasTimedCommand ( const string &  alias,
const vector< float > &  values,
const vector< int > &  timeOffsets,
const string &  type = "Merge",
const string &  type2 = "time-mixed" 
)

Definition at line 328 of file romeo.cpp.

void Romeo::DCMTimedCommand ( const string &  key,
const AL::ALValue &  value,
const int &  timeOffset,
const string &  type = "Merge" 
)

Definition at line 305 of file romeo.cpp.

void Romeo::declareEvent ( const string &  name)

Definition at line 441 of file romeo.cpp.

Definition at line 250 of file romeo.cpp.

AL::ALValue Romeo::getDataFromMemory ( const string &  key)

Definition at line 363 of file romeo.cpp.

Definition at line 487 of file romeo.cpp.

Definition at line 47 of file romeo.cpp.

Definition at line 143 of file romeo.cpp.

void Romeo::insertDataToMemory ( const string &  key,
const AL::ALValue &  value 
)

Definition at line 358 of file romeo.cpp.

Definition at line 280 of file romeo.cpp.

Definition at line 463 of file romeo.cpp.

Definition at line 583 of file romeo.cpp.

void Romeo::raiseEvent ( const string &  name,
const AL::ALValue &  value 
)

Definition at line 417 of file romeo.cpp.

void Romeo::raiseMicroEvent ( const string &  name,
const AL::ALValue &  value 
)

Definition at line 429 of file romeo.cpp.

Definition at line 560 of file romeo.cpp.

void Romeo::run ( )

Definition at line 453 of file romeo.cpp.

void Romeo::subscribe ( )

Definition at line 265 of file romeo.cpp.

void Romeo::subscribeToEvent ( const std::string &  name,
const std::string &  callback_module,
const std::string &  callback_method 
)

Definition at line 368 of file romeo.cpp.

void Romeo::subscribeToMicroEvent ( const std::string &  name,
const std::string &  callback_module,
const std::string &  callback_method,
const string &  callback_message = "" 
)

Definition at line 380 of file romeo.cpp.

bool Romeo::switchStiffnesses ( romeo_dcm_msgs::BoolService::Request &  req,
romeo_dcm_msgs::BoolService::Response &  res 
)

Definition at line 635 of file romeo.cpp.

void Romeo::unsubscribeFromEvent ( const string &  name,
const string &  callback_module 
)

Definition at line 393 of file romeo.cpp.

void Romeo::unsubscribeFromMicroEvent ( const string &  name,
const string &  callback_module 
)

Definition at line 405 of file romeo.cpp.

Definition at line 597 of file romeo.cpp.


Member Data Documentation

string Romeo::body_type_ [private]

Definition at line 111 of file romeo.h.

Definition at line 89 of file romeo.h.

AL::ALValue Romeo::commands_ [private]

Definition at line 105 of file romeo.h.

double Romeo::controller_freq_ [private]

Definition at line 115 of file romeo.h.

boost::shared_ptr<AL::ALProxy> Romeo::dcm_proxy_ [private]

Definition at line 119 of file romeo.h.

diagnostic_updater::Updater Romeo::diagnostic_ [private]

Definition at line 102 of file romeo.h.

double Romeo::high_freq_ [private]

Definition at line 115 of file romeo.h.

bool Romeo::is_connected_ [private]

Definition at line 108 of file romeo.h.

Definition at line 127 of file romeo.h.

Definition at line 126 of file romeo.h.

vector<double> Romeo::joint_angles_ [private]

Definition at line 132 of file romeo.h.

vector<double> Romeo::joint_commands_ [private]

Definition at line 131 of file romeo.h.

vector<double> Romeo::joint_efforts_ [private]

Definition at line 134 of file romeo.h.

vector<string> Romeo::joint_names_ [private]

Definition at line 130 of file romeo.h.

double Romeo::joint_precision_ [private]

Definition at line 115 of file romeo.h.

vector<double> Romeo::joint_velocities_ [private]

Definition at line 133 of file romeo.h.

vector<string> Romeo::joints_names_ [private]

Definition at line 123 of file romeo.h.

double Romeo::low_freq_ [private]

Definition at line 115 of file romeo.h.

sensor_msgs::JointState Romeo::m_jointState [private]

Definition at line 96 of file romeo.h.

Definition at line 92 of file romeo.h.

boost::shared_ptr<AL::ALMotionProxy> Romeo::m_motionProxy [private]

Definition at line 120 of file romeo.h.

Definition at line 99 of file romeo.h.

AL::ALMemoryProxy Romeo::memory_proxy_ [private]

Definition at line 118 of file romeo.h.

Definition at line 86 of file romeo.h.

int Romeo::number_of_joints_ [private]

Definition at line 129 of file romeo.h.

string Romeo::odom_frame_ [private]

Definition at line 114 of file romeo.h.

string Romeo::prefix_ [private]

Definition at line 114 of file romeo.h.

std_msgs::Float32 Romeo::stiffness_ [private]

Definition at line 95 of file romeo.h.

Definition at line 91 of file romeo.h.

Definition at line 97 of file romeo.h.

Definition at line 112 of file romeo.h.

int Romeo::topic_queue_ [private]

Definition at line 113 of file romeo.h.

string Romeo::version_ [private]

Definition at line 111 of file romeo.h.


The documentation for this class was generated from the following files:


romeo_dcm_driver
Author(s): Konstantinos Chatzilygeroudis , Ha Dang
autogenerated on Fri Jun 24 2016 04:21:15