Public Member Functions | Private Attributes
Nao Class Reference

#include <nao.h>

Inheritance diagram for Nao:
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 ()
 Nao (boost::shared_ptr< AL::ALBroker > broker, const std::string &name)
void publishBaseFootprint (const ros::Time &ts)
void raiseEvent (const string &name, const AL::ALValue &value)
void raiseMicroEvent (const string &name, const AL::ALValue &value)
void readJoints ()
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 (nao_dcm_msgs::BoolService::Request &req, nao_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 ()
 ~Nao ()

Private Attributes

tf::TransformBroadcaster base_footprint_broadcaster_
tf::TransformListener base_footprint_listener_
string body_type_
ros::Subscriber cmd_vel_sub_
AL::ALValue commands_
double controller_freq_
AL::DCMProxy dcm_proxy_
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< string > joint_temperature_names_
vector< double > joint_velocities_
vector< string > joints_names_
double low_freq_
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 75 of file nao.h.


Constructor & Destructor Documentation

Nao::Nao ( 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 29 of file nao.cpp.

Nao::~Nao ( )

Definition at line 38 of file nao.cpp.


Member Function Documentation

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

Definition at line 286 of file nao.cpp.

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

Definition at line 546 of file nao.cpp.

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

Definition at line 184 of file nao.cpp.

bool Nao::connected ( )

Definition at line 541 of file nao.cpp.

Definition at line 500 of file nao.cpp.

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

Definition at line 315 of file nao.cpp.

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

Definition at line 292 of file nao.cpp.

void Nao::declareEvent ( const string &  name)

Definition at line 428 of file nao.cpp.

void Nao::disconnect ( )

Definition at line 242 of file nao.cpp.

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

Definition at line 350 of file nao.cpp.

bool Nao::initialize ( )

Definition at line 44 of file nao.cpp.

Definition at line 145 of file nao.cpp.

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

Definition at line 345 of file nao.cpp.

void Nao::loadParams ( )

Definition at line 268 of file nao.cpp.

void Nao::publishBaseFootprint ( const ros::Time ts)

Definition at line 552 of file nao.cpp.

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

Definition at line 404 of file nao.cpp.

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

Definition at line 416 of file nao.cpp.

void Nao::readJoints ( )

Definition at line 595 of file nao.cpp.

void Nao::run ( )

Definition at line 440 of file nao.cpp.

void Nao::subscribe ( )

Definition at line 257 of file nao.cpp.

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

Definition at line 355 of file nao.cpp.

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

Definition at line 367 of file nao.cpp.

bool Nao::switchStiffnesses ( nao_dcm_msgs::BoolService::Request &  req,
nao_dcm_msgs::BoolService::Response &  res 
)

Definition at line 652 of file nao.cpp.

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

Definition at line 380 of file nao.cpp.

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

Definition at line 392 of file nao.cpp.

void Nao::writeJoints ( )

Definition at line 616 of file nao.cpp.


Member Data Documentation

Definition at line 84 of file nao.h.

Definition at line 85 of file nao.h.

string Nao::body_type_ [private]

Definition at line 100 of file nao.h.

Definition at line 82 of file nao.h.

AL::ALValue Nao::commands_ [private]

Definition at line 94 of file nao.h.

double Nao::controller_freq_ [private]

Definition at line 104 of file nao.h.

AL::DCMProxy Nao::dcm_proxy_ [private]

Definition at line 108 of file nao.h.

double Nao::high_freq_ [private]

Definition at line 104 of file nao.h.

bool Nao::is_connected_ [private]

Definition at line 97 of file nao.h.

Definition at line 115 of file nao.h.

Definition at line 114 of file nao.h.

vector<double> Nao::joint_angles_ [private]

Definition at line 120 of file nao.h.

vector<double> Nao::joint_commands_ [private]

Definition at line 119 of file nao.h.

vector<double> Nao::joint_efforts_ [private]

Definition at line 122 of file nao.h.

vector<string> Nao::joint_names_ [private]

Definition at line 118 of file nao.h.

double Nao::joint_precision_ [private]

Definition at line 104 of file nao.h.

vector<string> Nao::joint_temperature_names_ [private]

Definition at line 112 of file nao.h.

vector<double> Nao::joint_velocities_ [private]

Definition at line 121 of file nao.h.

vector<string> Nao::joints_names_ [private]

Definition at line 111 of file nao.h.

double Nao::low_freq_ [private]

Definition at line 104 of file nao.h.

Definition at line 91 of file nao.h.

AL::ALMemoryProxy Nao::memory_proxy_ [private]

Definition at line 107 of file nao.h.

Definition at line 79 of file nao.h.

int Nao::number_of_joints_ [private]

Definition at line 117 of file nao.h.

string Nao::odom_frame_ [private]

Definition at line 103 of file nao.h.

string Nao::prefix_ [private]

Definition at line 103 of file nao.h.

std_msgs::Float32 Nao::stiffness_ [private]

Definition at line 88 of file nao.h.

Definition at line 87 of file nao.h.

Definition at line 89 of file nao.h.

bool Nao::stiffnesses_enabled_ [private]

Definition at line 101 of file nao.h.

int Nao::topic_queue_ [private]

Definition at line 102 of file nao.h.

string Nao::version_ [private]

Definition at line 100 of file nao.h.


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


nao_dcm_driver
Author(s): Konstantinos Chatzilygeroudis
autogenerated on Wed Oct 19 2016 03:58:50