#include <signal.h>#include <ros/ros.h>#include <ros/console.h>#include <controller_manager/controller_manager.h>#include <crane_x7_control/dxlport_control.h>#include <std_msgs/Int32.h>#include <std_msgs/Int16.h>#include <std_msgs/UInt16.h>#include <std_msgs/Int8.h>#include <std_msgs/String.h>#include <std_msgs/Float64.h>#include <sstream>#include <queue>
Go to the source code of this file.
Classes | |
| struct | SET_GAIN_QUEUE |
Macros | |
| #define | CONTROL_HZ (200) |
Typedefs | |
| typedef dynamic_reconfigure::Server< crane_x7_msgs::ServoParameterConfig > | RECONFIG_TYPE |
| typedef struct SET_GAIN_QUEUE | ST_SET_GAIN_QUEUE |
Functions | |
| void | gainCallback (const ros::MessageEvent< std_msgs::UInt16 const > &event) |
| void | init_reconfigure (DXLPORT_CONTROL *driver) |
| void | init_topics (DXLPORT_CONTROL *driver, ros::NodeHandle nh) |
| int | main (int argc, char *argv[]) |
| void | publish_topic_data (DXLPORT_CONTROL *driver, bool temp_flg) |
| void | reconfigureCallback (crane_x7_msgs::ServoParameterConfig &config, uint32_t level, uint8_t id) |
| void | SigintHandler (int sig) |
| std::vector< std::string > | split (const std::string &input, char delimiter) |
| void | write_joint_param (DXLPORT_CONTROL &driver, ST_JOINT_PARAM set_param) |
Variables | |
| static std::vector< ros::Publisher > | current_pub |
| static DXLPORT_CONTROL * | driver_addr |
| static std::vector< ros::Publisher > | dxl_position_pub |
| static std::vector< ros::Subscriber > | gain_sub |
| static std_msgs::String | lasterror_out |
| static std::vector< std::unique_ptr< RECONFIG_TYPE > > | reconfig_srv |
| static std::queue< ST_SET_GAIN_QUEUE > | set_gain_request |
| static std::queue< ST_JOINT_PARAM > | set_joint_param_request |
| static std::vector< ros::Publisher > | temp_pub |
| #define CONTROL_HZ (200) |
Definition at line 21 of file hardware.cpp.
| typedef dynamic_reconfigure::Server<crane_x7_msgs::ServoParameterConfig> RECONFIG_TYPE |
Definition at line 29 of file hardware.cpp.
| typedef struct SET_GAIN_QUEUE ST_SET_GAIN_QUEUE |
| void gainCallback | ( | const ros::MessageEvent< std_msgs::UInt16 const > & | event | ) |
Definition at line 64 of file hardware.cpp.
| void init_reconfigure | ( | DXLPORT_CONTROL * | driver | ) |
Definition at line 153 of file hardware.cpp.
| void init_topics | ( | DXLPORT_CONTROL * | driver, |
| ros::NodeHandle | nh | ||
| ) |
Definition at line 132 of file hardware.cpp.
| int main | ( | int | argc, |
| char * | argv[] | ||
| ) |
Definition at line 216 of file hardware.cpp.
| void publish_topic_data | ( | DXLPORT_CONTROL * | driver, |
| bool | temp_flg | ||
| ) |
Definition at line 164 of file hardware.cpp.
| void reconfigureCallback | ( | crane_x7_msgs::ServoParameterConfig & | config, |
| uint32_t | level, | ||
| uint8_t | id | ||
| ) |
Definition at line 87 of file hardware.cpp.
| void SigintHandler | ( | int | sig | ) |
Definition at line 211 of file hardware.cpp.
| std::vector<std::string> split | ( | const std::string & | input, |
| char | delimiter | ||
| ) |
Definition at line 52 of file hardware.cpp.
| void write_joint_param | ( | DXLPORT_CONTROL & | driver, |
| ST_JOINT_PARAM | set_param | ||
| ) |
Definition at line 194 of file hardware.cpp.
|
static |
Definition at line 25 of file hardware.cpp.
|
static |
Definition at line 31 of file hardware.cpp.
|
static |
Definition at line 26 of file hardware.cpp.
|
static |
Definition at line 28 of file hardware.cpp.
|
static |
Definition at line 24 of file hardware.cpp.
|
static |
Definition at line 30 of file hardware.cpp.
|
static |
Definition at line 48 of file hardware.cpp.
|
static |
Definition at line 50 of file hardware.cpp.
|
static |
Definition at line 27 of file hardware.cpp.