45 std::string port_upper;
46 std::string port_lower;
49 robot_hw_nh.
param<std::string>(
"port_upper", port_upper,
"/dev/aero_upper");
50 robot_hw_nh.
param<std::string>(
"port_lower", port_lower,
"/dev/aero_lower");
52 "seed_r7_robot_interface/TypeF");
54 if (robot_hw_nh.
hasParam(
"/joint_settings/upper"))
57 ROS_WARN(
"/joint_settings/upper read error");
59 if (robot_hw_nh.
hasParam(
"/joint_settings/lower"))
62 ROS_WARN(
"/joint_settings/lower read error");
64 if (robot_hw_nh.
hasParam(
"controller_rate")) {
66 robot_hw_nh.
getParam(
"controller_rate", rate);
71 if (robot_hw_nh.
hasParam(
"overlap_scale")) {
73 robot_hw_nh.
getParam(
"overlap_scale", scl);
79 ROS_INFO(
"upper_port: %s", port_upper.c_str());
80 ROS_INFO(
"lower_port: %s", port_lower.c_str());
91 ROS_ERROR(
"Failed to initiate stroke converter");
106 std::string model_str;
107 if (!root_nh.
getParam(
"robot_description", model_str)) {
108 ROS_ERROR(
"Failed to get model from robot_description");
113 ROS_ERROR(
"Failed to parse robot_description");
117 ROS_DEBUG(
"read %d joints", number_of_angles_);
157 const bool urdf_limits_ok
159 if (!urdf_limits_ok) {
160 ROS_WARN(
"urdf limits of joint %s is not defined", jointname.c_str());
175 ROS_INFO(
"Upper Firmware Ver. is [ %s ]",
controller_upper_->getFirmwareVersion().c_str() );
176 ROS_INFO(
"Lower Firmware Ver. is [ %s ]",
controller_lower_->getFirmwareVersion().c_str() );
195 std::thread t1([&](){
198 std::thread t2([&](){
208 std::vector<int16_t> act_strokes(0);
209 std::vector<int16_t> act_upper_strokes;
210 std::vector<int16_t> act_lower_strokes;
216 act_strokes.insert(act_strokes.end(),act_upper_strokes.begin(),act_upper_strokes.end());
217 act_strokes.insert(act_strokes.end(),act_lower_strokes.begin(),act_lower_strokes.end());
220 std::vector<double> act_positions;
226 double tm = period.
toSec();
228 float position = act_positions[j];
229 float velocity = 0.0;
249 ROS_WARN(
"The robot is protective stopped, please release it.");
267 case ControlMethod::POSITION:
272 case ControlMethod::VELOCITY:
276 case ControlMethod::EFFORT:
280 case ControlMethod::POSITION_PID:
284 case ControlMethod::VELOCITY_PID:
291 std::vector<bool > mask_positions(number_of_angles_);
292 std::fill(mask_positions.begin(), mask_positions.end(),
true);
295 std::vector<int16_t> ref_strokes(ref_positions.size());
299 double tmp = ref_strokes[i];
301 mask_positions[i] =
false;
307 std::vector<int16_t> snt_strokes(ref_strokes);
308 for (
size_t i = 0; i < ref_strokes.size() ; ++i) {
309 if (!mask_positions[i]) snt_strokes[i] = 0x7FFF;
313 std::vector<int16_t> upper_strokes;
314 std::vector<int16_t> lower_strokes;
327 std::thread t1([&](){
330 std::thread t2([&](){
356 ROS_INFO(
"sendnum : %d, script : %d", _number, _script);
378 std_msgs::Float32 voltage;
427 stat.summary(2,
"Now calibrating, or the USB cable is plugged out");
430 stat.summary(2,
"Power failed, pleae check the battery");
433 stat.summary(2,
"Connection error occurred, please check the cable");
436 stat.summary(2,
"Motor driver is high temperature, please reboot the robot");
439 stat.summary(2,
"Protective stopped, please release it");
442 stat.summary(2,
"Calibration error occurred, please recalibration");
445 stat.summary(1,
"Step-out has occurred");
448 stat.summary(1,
"Response error has occurred");
451 stat.summary(0,
"System all green");
455 stat.summary(2,
"E-Stop switch is pushed, please release it");
458 stat.add(
"Communication Error",
comm_err_);
472 (seed_r7_ros_controller::ResetRobotStatus::Request& _req,
473 seed_r7_ros_controller::ResetRobotStatus::Response& _res)
481 _res.result =
"reset status succeeded";
void registerInterface(T *iface)
void turnWheel(std::vector< int16_t > &_vel)
hardware_interface::JointStateInterface js_interface_
void publish(const boost::shared_ptr< M > &message) const
void runLedScript(uint8_t _number, uint16_t _script)
URDF_EXPORT bool initString(const std::string &xmlstring)
void onWheelServo(bool _value)
bool resetRobotStatusCallback(seed_r7_ros_controller::ResetRobotStatus::Request &_req, seed_r7_ros_controller::ResetRobotStatus::Response &_res)
void setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
unsigned int number_of_angles_
boost::shared_ptr< seed_converter::StrokeConverter > stroke_converter_
ros::Publisher bat_vol_pub_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
boost::shared_ptr< robot_hardware::UpperController > controller_upper_
void enforceLimits(const ros::Duration &period)
struct robot_hardware::RobotHW::RobotStatus robot_status_
std::vector< std::string > joint_names_upper_
std::vector< std::string > joint_names_lower_
boost::shared_ptr< robot_hardware::LowerController > controller_lower_
std::vector< double > joint_position_
pluginlib::ClassLoader< seed_converter::StrokeConverter > converter_loader_
std::vector< double > prev_ref_strokes_
std::vector< double > joint_effort_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::vector< double > joint_position_command_
std::vector< double > joint_effort_command_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void getBatteryVoltage(const ros::TimerEvent &_event)
hardware_interface::PositionJointInterface pj_interface_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< JointType > joint_types_
std::vector< ControlMethod > joint_control_methods_
void registerHandle(const JointStateHandle &handle)
void readPos(const ros::Time &time, const ros::Duration &period, bool update)
JointStateHandle getHandle(const std::string &name)
ros::ServiceServer reset_robot_status_server_
diagnostic_updater::Updater diagnostic_updater_
ros::Timer bat_vol_timer_
bool getParam(const std::string &key, std::string &s) const
std::vector< double > joint_velocity_
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
std::vector< std::string > joint_list_
std::vector< double > joint_velocity_command_
bool hasParam(const std::string &key) const
std::string robot_model_plugin_
virtual void read(const ros::Time &time, const ros::Duration &period)
void runHandScript(uint8_t _number, uint16_t _script, uint8_t _current)
virtual void write(const ros::Time &time, const ros::Duration &period)
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)