#include <romeo.h>
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::ControllerManager * | manager_ |
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_ |
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.
Romeo::~Romeo | ( | ) |
void Romeo::brokerDisconnected | ( | const string & | event_name, |
const string & | broker_name, | ||
const string & | subscriber_identifier | ||
) |
void Romeo::commandVelocity | ( | const geometry_msgs::TwistConstPtr & | msg | ) |
bool Romeo::connect | ( | const ros::NodeHandle | nh | ) |
bool Romeo::connected | ( | ) |
void Romeo::controllerLoop | ( | ) |
void Romeo::DCMAliasTimedCommand | ( | const string & | alias, |
const vector< float > & | values, | ||
const vector< int > & | timeOffsets, | ||
const string & | type = "Merge" , |
||
const string & | type2 = "time-mixed" |
||
) |
void Romeo::DCMTimedCommand | ( | const string & | key, |
const AL::ALValue & | value, | ||
const int & | timeOffset, | ||
const string & | type = "Merge" |
||
) |
void Romeo::declareEvent | ( | const string & | name | ) |
void Romeo::disconnect | ( | ) |
AL::ALValue Romeo::getDataFromMemory | ( | const string & | key | ) |
void Romeo::highCommunicationLoop | ( | ) |
bool Romeo::initialize | ( | ) |
void Romeo::insertDataToMemory | ( | const string & | key, |
const AL::ALValue & | value | ||
) |
void Romeo::loadParams | ( | ) |
void Romeo::lowCommunicationLoop | ( | ) |
void Romeo::publishJointStateFromAlMotion | ( | ) |
void Romeo::raiseEvent | ( | const string & | name, |
const AL::ALValue & | value | ||
) |
void Romeo::raiseMicroEvent | ( | const string & | name, |
const AL::ALValue & | value | ||
) |
void Romeo::readJoints | ( | ) |
void Romeo::run | ( | ) |
void Romeo::subscribe | ( | ) |
void Romeo::subscribeToEvent | ( | const std::string & | name, |
const std::string & | callback_module, | ||
const std::string & | callback_method | ||
) |
void Romeo::subscribeToMicroEvent | ( | const std::string & | name, |
const std::string & | callback_module, | ||
const std::string & | callback_method, | ||
const string & | callback_message = "" |
||
) |
bool Romeo::switchStiffnesses | ( | romeo_dcm_msgs::BoolService::Request & | req, |
romeo_dcm_msgs::BoolService::Response & | res | ||
) |
void Romeo::unsubscribeFromEvent | ( | const string & | name, |
const string & | callback_module | ||
) |
void Romeo::unsubscribeFromMicroEvent | ( | const string & | name, |
const string & | callback_module | ||
) |
void Romeo::writeJoints | ( | ) |
string Romeo::body_type_ [private] |
ros::Subscriber Romeo::cmd_vel_sub_ [private] |
AL::ALValue Romeo::commands_ [private] |
double Romeo::controller_freq_ [private] |
boost::shared_ptr<AL::ALProxy> Romeo::dcm_proxy_ [private] |
diagnostic_updater::Updater Romeo::diagnostic_ [private] |
double Romeo::high_freq_ [private] |
bool Romeo::is_connected_ [private] |
vector<double> Romeo::joint_angles_ [private] |
vector<double> Romeo::joint_commands_ [private] |
vector<double> Romeo::joint_efforts_ [private] |
vector<string> Romeo::joint_names_ [private] |
double Romeo::joint_precision_ [private] |
vector<double> Romeo::joint_velocities_ [private] |
vector<string> Romeo::joints_names_ [private] |
double Romeo::low_freq_ [private] |
sensor_msgs::JointState Romeo::m_jointState [private] |
ros::Publisher Romeo::m_jointStatePub [private] |
boost::shared_ptr<AL::ALMotionProxy> Romeo::m_motionProxy [private] |
AL::ALMemoryProxy Romeo::memory_proxy_ [private] |
ros::NodeHandle Romeo::node_handle_ [private] |
int Romeo::number_of_joints_ [private] |
string Romeo::odom_frame_ [private] |
string Romeo::prefix_ [private] |
std_msgs::Float32 Romeo::stiffness_ [private] |
ros::Publisher Romeo::stiffness_pub_ [private] |
ros::ServiceServer Romeo::stiffness_switch_ [private] |
bool Romeo::stiffnesses_enabled_ [private] |
int Romeo::topic_queue_ [private] |
string Romeo::version_ [private] |