SMORES Robot Platform Simulation
Modlab at Penn, ASL at Cornell
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends
gazebo::ConfigEditor Class Reference

Configuration Editor customized worldplugin. More...

#include <ConfigEditor.hh>

Inheritance diagram for gazebo::ConfigEditor:
gazebo::WorldServer

Public Member Functions

 ConfigEditor ()
 Constructor.
 
 ~ConfigEditor ()
 Deconstructor.
 
virtual void InsertModel (string name, math::Pose position, string joint_angles)
 Insert a default muscle module. More...
 
virtual void InsertModel (string name, math::Pose position, string joint_angles, string model_path)
 Insert a different type of module by specifying the sdf file path. More...
 
virtual void ExtraInitializationInLoad (physics::WorldPtr _parent, sdf::ElementPtr _sdf)
 The function that perform extra initialization. More...
 
void ExtraWorkWhenModelInserted (CommandMessagePtr &msg)
 Need to be set to empty so the world plugin will not read in gaits. More...
 
- Public Member Functions inherited from gazebo::WorldServer
LibraryTemplateDynamicallyLoadedLibrary (const char *library_path, void *lib_handle)
 Load a shared library in linux.
 
void CloseLoadedLibrary (void **lib_handle)
 Close the loaded libraries.
 
virtual void OnSystemRunningExtra (const common::UpdateInfo &_info)
 
void AddInitialPosition (math::Pose position)
 Add a new position to set at the end of 'intialPosition' vector.
 
void AddInitialJoints (string joint_angles)
 Add new initial joint values to set at the end of 'initalJointValue' vector.
 
void DeleteSmoresmodulePtr (string module_name)
 Delete the smoresmodule object in the world. More...
 
void DeleteModule (string module_name)
 Delete a model that already in the world. More...
 
void DeleteAllModules (void)
 Delete all models that already in the world.
 
math::Vector3 GetCurrentConfigurationPose (void)
 Get the current position in world of the inserted configuration. More...
 
void BuildConfigurationFromXML (string file_name)
 Build a configuration at origin using a XML file.
 
void BuildConfigurationFromXML (string file_name, math::Vector3 initial_pose)
 Build a configuration at given initial_pose using a XML file.
 
void BuildConnectionFromXML (string file_name)
 This function is used to build connection using a XML file.
 
double ConversionForAngleOverPi (double angle)
 Convert angles so that their absolutely value always smaller than Pi.
 
void EnableAutoMagneticConnection (void)
 
void PassiveConnect (SmoresModulePtr module_1, SmoresModulePtr module_2, int node1_ID, int node2_ID, double node_angle, double node_distance)
 Connect two modules by pointers and node_ID.
 
void PassiveConnect (SmoresModulePtr module_1, SmoresModulePtr module_2, int node1_ID, int node2_ID)
 With default angle and distance offset equal to 0.
 
void ActiveConnect (SmoresModulePtr module_1, SmoresModulePtr module_2, int node1_ID, int node2_ID, double node_angle, double node_distance)
 TODO: Need add 'active' feature to this function.
 
void ActiveConnect (SmoresModulePtr module_1, SmoresModulePtr module_2, int node1_ID, int node2_ID)
 With default angle and distance offset equal to 0.
 
void Disconnect (SmoresEdgePtr aEdge)
 
void Disconnect (SmoresModulePtr aModule, int node_ID)
 Disconnect two module base on one module and one node of that module.
 
void Disconnect (string moduleName, int node_ID)
 Disconnect two module base on one module and one node of that module.
 
void Disconnect (string moduleName1, string moduleName2)
 Disconnect two module base on their names.
 
void SendGaitTable (SmoresModulePtr module, const int *flag, const double *gait_value, int msg_type, unsigned int time_stamp, string condition_str, string dependency_str)
 Send time based common gait with condition and dependency. More...
 
void SendGaitTable (SmoresModulePtr module, const int *flag, const double *gait_value, int msg_type, unsigned int time_stamp)
 Send time based common gait without condition and dependency. More...
 
void SendGaitTable (SmoresModulePtr module, const int *flag, const double *gait_value, int msg_type, string condition_str, string dependency_str)
 Send common gait with condition and dependency. More...
 
void SendGaitTable (SmoresModulePtr module, const int *flag, const double *gait_value, int msg_type)
 Send common gait without condition and dependency. More...
 
void SendGaitTable (SmoresModulePtr module, int joint_ID, double gait_value, int msg_type, unsigned int time_stamp, string condition_str, string dependency_str)
 Send gait table to change a single joint of a module. More...
 
void SendGaitTable (SmoresModulePtr module, int joint_ID, double gait_value, int msg_type, unsigned int time_stamp)
 Send gait table to change a single joint of a module. More...
 
void SendGaitTable (SmoresModulePtr module, int joint_ID, double gait_value, int msg_type, string condition_str, string dependency_str)
 Send gait table to change a single joint of a module. More...
 
void SendGaitTable (SmoresModulePtr module, int joint_ID, double gait_value, int msg_type)
 Send gait table to change a single joint of a module. More...
 
void SendGaitTable (SmoresModulePtr module, string module1, string module2, int node1, int node2, int commandtype, unsigned int time_stamp, string condition_str, string dependency_str)
 
void SendGaitTable (SmoresModulePtr module, string module1, string module2, int node1, int node2, int commandtype, unsigned int time_stamp)
 
void SendGaitTable (SmoresModulePtr module, string module1, string module2, int node1, int node2, int commandtype, string condition_str, string dependency_str)
 
void SendGaitTable (SmoresModulePtr module, string module1, string module2, int node1, int node2, int commandtype)
 
void SendGaitTableInstance (SmoresModulePtr module, const int *flag, const double *gait_value, int msg_type)
 Used in the direct driving situation, ignore execution order. More...
 
void SendGaitTableInstance (SmoresModulePtr module, const int *flag, const double *gait_value)
 Used in the direct driving situation with default type 4. More...
 
void SendPositionInstance (SmoresModulePtr module, double x, double y, double orientation_angle)
 Used in direct control, dirve a module to a specific position. More...
 
void EraseComaands (SmoresModulePtr module)
 
void DynamicJointDestroy (SmoresEdgePtr aEdge)
 
void ReBuildDynamicJoint (SmoresEdgePtr a_edge)
 Rebuild the dynamic joint using the information in the edge object.
 
int GetNodeIDByName (string node_name)
 
bool CheckModuleExistByName (string module_name)
 Get return true if the smores module with given name exist in the world.
 
SmoresModulePtr GetModulePtrByName (string module_name)
 Get SmoresModule object by specifying the name. More...
 
SmoresModulePtr GetModulePtrByIDX (unsigned int idx)
 Get SmoresModule object by specifying the index in the vector moduleList.
 
unsigned int GetModuleListSize (void)
 Get the count of the modules that are in the list.
 
void EraseCommandPtrByModule (SmoresModulePtr module_ptr)
 
int GetModuleIndexByName (string module_name)
 
bool AlreadyConnected (SmoresModulePtr module_1, SmoresModulePtr module_2, int node1_ID, int node2_ID)
 Check whether two nodes are connected together.
 
bool AlreadyConnected (SmoresModulePtr module_1, SmoresModulePtr module_2)
 Check whether two modules have already connected on a node.
 
bool AlreadyConnected (SmoresModulePtr module, int node_ID)
 Check whether a node a of module has been occupied.
 
void ReadFileAndGenerateCommands (const char *fileName)
 Read a 'gait table' stored in a text file.
 
void FigureInterpret (const vector< string > *joints_spec, int *type_flags, double *joint_values)
 Used to interpret the number in gait table. More...
 
void InterpretCommonGaitString (string a_command_str)
 Interpret normal command string. More...
 
void InterpretSpecialString (string a_command_str)
 Interpret special command. More...
 
unsigned int CountModules (SmoresModulePtr module)
 Count how many modules are there in a cluster with the current module. More...
 
unsigned int GetInitialJointSequenceSize (void)
 Get the length of the initial joint value setting sequence.
 
unsigned int GetEdgeCounts (void)
 Get the total counts of the edges that stored in the program.
 
SmoresEdgePtr GetEdgePtrByIDX (unsigned int idx)
 Get SmoresEdge object by specifying the index in the vector connectionEdges.
 

Additional Inherited Members

- Public Attributes inherited from gazebo::WorldServer
physics::WorldPtr currentWorld
 

Detailed Description

Configuration Editor customized worldplugin.

Member Function Documentation

void gazebo::ConfigEditor::ExtraInitializationInLoad ( physics::WorldPtr  _parent,
sdf::ElementPtr  _sdf 
)
virtual

The function that perform extra initialization.

Parameters
_parentgazebo world object
_sdfgazebo sdf object of the world

Reimplemented from gazebo::WorldServer.

void gazebo::ConfigEditor::ExtraWorkWhenModelInserted ( CommandMessagePtr &  msg)
virtual

Need to be set to empty so the world plugin will not read in gaits.

This function will be called in the command callback function when receiving messgae from model.

Parameters
msgreference of the command message object pointer

Reimplemented from gazebo::WorldServer.

void gazebo::ConfigEditor::InsertModel ( string  name,
math::Pose  position,
string  joint_angles 
)
virtual

Insert a default muscle module.

Parameters
nameModule name
positionposition of the inserted module
joint_anglesa string which has the value for four joint angles

Reimplemented from gazebo::WorldServer.

void gazebo::ConfigEditor::InsertModel ( string  name,
math::Pose  position,
string  joint_angles,
string  model_path 
)
virtual

Insert a different type of module by specifying the sdf file path.

Parameters
nameModule name
positionposition of the inserted module
joint_anglesa string which has the value for four joint angles
model_paththe path of the model sdf file

Reimplemented from gazebo::WorldServer.


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