18 #include <sensor_msgs/JointState.h> 20 #include <diagnostic_msgs/DiagnosticArray.h> 32 Robot::Robot(qi::SessionPtr session):
34 session_name_(
"naoqi_dcm_driver"),
36 nhPtr_(new
ros::NodeHandle(
"")),
41 controller_freq_(15.0),
42 joint_precision_(0.1),
45 stiffness_value_(0.9
f)
54 void Robot::stopService() {
62 motion_->setStiffnessArms(0.0f, 2.0f);
65 if (motor_groups_.size() == 1)
66 if (motor_groups_[0] ==
"Body")
71 motion_->setStiffnessArms(0.0f, 2.0f);
74 is_connected_ =
false;
83 bool Robot::initializeControllers(
const std::vector <std::string> &joints)
85 int joints_nbr = joints.size();
88 hw_angles_.reserve(joints_nbr);
89 hw_velocities_.reserve(joints_nbr);
90 hw_efforts_.reserve(joints_nbr);
91 hw_commands_.reserve(joints_nbr);
93 hw_angles_.resize(joints_nbr);
94 hw_velocities_.resize(joints_nbr);
95 hw_efforts_.resize(joints_nbr);
96 hw_commands_.resize(joints_nbr);
100 for(
int i=0; i<joints_nbr; ++i)
106 jnt_state_interface_.registerHandle(state_handle);
110 jnt_pos_interface_.registerHandle(pos_handle);
113 registerInterface(&jnt_state_interface_);
114 registerInterface(&jnt_pos_interface_);
118 ROS_ERROR(
"Could not initialize hardware interfaces!\n\tTrace: %s", e.what());
126 bool Robot::connect()
128 is_connected_ =
false;
142 std::string robot = memory_->getData(
"RobotConfig/Body/Type");
143 std::transform(robot.begin(), robot.end(), robot.begin(), ::tolower);
149 if (motor_groups_.size() == 1)
151 if (motor_groups_[0] ==
"Body")
156 if (!motion_->robotIsWakeUp())
158 ROS_ERROR(
"Please, wakeUp the robot to be able to set stiffness");
164 motion_->manageConcurrence();
167 qi_joints_ = motion_->getBodyNamesFromGroup(motor_groups_);
168 if (qi_joints_.empty())
169 ROS_ERROR(
"Controlled joints are not known.");
171 if (hw_joints_.empty())
173 ROS_INFO_STREAM(
"Initializing the HW controlled joints with Naoqi joints.");
174 hw_joints_.reserve(qi_joints_.size());
175 copy(qi_joints_.begin(), qi_joints_.end(), back_inserter(hw_joints_));
179 ignoreMimicJoints(&qi_joints_);
181 qi_commands_.reserve(qi_joints_.size());
182 qi_commands_.resize(qi_joints_.size(), 0.0);
185 memory_->init(qi_joints_);
186 motion_->init(qi_joints_);
188 dcm_->init(qi_joints_);
190 hw_enabled_ = checkJoints();
193 joint_states_topic_.header.frame_id =
"base_link";
194 joint_states_topic_.name = motion_->getBodyNames(
"Body");
195 joint_states_topic_.position.resize(joint_states_topic_.name.size());
198 std::vector<std::string> joints_all_names = motion_->getBodyNames(
"JointActuators");
200 new Diagnostics(_session, &diag_pub_, joints_all_names, robot));
202 is_connected_ =
true;
208 if (!setStiffness(stiffness_value_))
218 ROS_ERROR(
"Could not initialize controller manager!\n\tTrace: %s", e.what());
222 if(!initializeControllers(hw_joints_))
229 void Robot::subscribe()
232 cmd_moveto_sub_ = nhPtr_->subscribe(prefix_+
"cmd_moveto", 1, &Robot::commandVelocity,
this);
234 diag_pub_ = nhPtr_->advertise<diagnostic_msgs::DiagnosticArray>(prefix_+
"diagnostics", topic_queue_);
236 stiffness_pub_ = nhPtr_->advertise<std_msgs::Float32>(prefix_+
"stiffnesses", topic_queue_);
237 stiffness_.data = 1.0f;
239 joint_states_pub_ = nhPtr_->advertise<sensor_msgs::JointState>(
"/joint_states", topic_queue_);
242 bool Robot::loadParams()
246 nh.getParam(
"BodyType", body_type_);
247 nh.getParam(
"TopicQueue", topic_queue_);
248 nh.getParam(
"HighCommunicationFrequency", high_freq_);
249 nh.getParam(
"ControllerFrequency", controller_freq_);
250 nh.getParam(
"JointPrecision", joint_precision_);
251 nh.getParam(
"OdomFrame", odom_frame_);
252 nh.getParam(
"use_dcm", use_dcm_);
254 if (nh.hasParam(
"max_stiffness"))
255 nh.getParam(
"max_stiffness", stiffness_value_);
259 <<
"You have chosen to control the robot based on DCM. " 260 <<
"It leads to concurrence between DCM and ALMotion, and " 261 <<
"it can cause shaking the robot. " 262 <<
"If the robot starts shaking, stop the node (Ctrl+C). " 263 <<
"Use either ALMotion or stop ALMotion and use DCM only.");
266 nh.getParam(
"Prefix", prefix_);
267 if (prefix_.length() > 0)
268 if (prefix_.at(prefix_.length()-1) !=
'/')
273 nh.getParam(
"pepper_dcm", params_pepper_dcm);
275 ROS_ERROR(
"Please ensure that the list of controllers is TypeStruct");
277 XmlRpc::XmlRpcValue::ValueStruct::const_iterator it=params_pepper_dcm.
begin();
278 for (; it != params_pepper_dcm.
end(); ++it)
280 XmlRpc::XmlRpcValue::ValueStruct::const_iterator it2 = params_pepper_dcm[it->first].
begin();
281 for (; it2 != params_pepper_dcm[it->first].
end(); ++it2)
283 std::string
param = (std::string)(it2->first);
284 if (param.compare(
"joints") == 0)
297 std::string motor_groups_temp =
"";
298 nh.getParam(
"motor_groups", motor_groups_temp);
299 motor_groups_ =
toVector(motor_groups_temp);
300 if (motor_groups_.empty())
302 motor_groups_.push_back(
"LArm");
303 motor_groups_.push_back(
"RArm");
313 void Robot::controllerLoop()
325 stiffness_pub_.publish(stiffness_);
327 if (!diagnostics_->publish())
336 manager_->update(time,
ros::Duration(1.0f/controller_freq_));
354 bool Robot::isConnected()
356 return is_connected_;
359 void Robot::commandVelocity(
const geometry_msgs::TwistConstPtr &msg)
363 motion_->setStiffnessArms(0.0f, 1.0f);
365 motion_->moveTo(msg->linear.x, msg->linear.y, msg->angular.z);
370 motion_->setStiffnessArms(1.0f, 1.0f);
373 void Robot::publishBaseFootprint(
const ros::Time &ts)
375 std::string odom_frame, base_link_frame;
378 odom_frame = base_footprint_listener_.resolve(odom_frame_);
379 base_link_frame = base_footprint_listener_.resolve(
"base_link");
388 double temp_freq = 1.0f/(10.0*high_freq_);
389 if(!base_footprint_listener_.waitForTransform(odom_frame, base_link_frame,
ros::Time(0),
ros::Duration(temp_freq)))
393 base_footprint_listener_.lookupTransform(odom_frame, base_link_frame,
ros::Time(0), tf_odom_to_base);
403 new_origin.
setZ(height);
405 double roll, pitch, yaw;
412 base_link_frame,
"base_footprint"));
415 std::vector <bool> Robot::checkJoints()
417 std::vector <bool> hw_enabled;
418 hw_enabled.reserve(hw_joints_.size());
419 hw_enabled.resize(hw_joints_.size(),
false);
422 std::vector<std::string>::iterator hw_j = hw_joints_.begin();
423 std::vector<std::string>::iterator qi_j = qi_joints_.begin();
424 std::vector<bool>::iterator hw_enabled_j = hw_enabled.begin();
426 for(; hw_j != hw_joints_.end(); ++hw_j, ++hw_enabled_j)
430 *hw_enabled_j =
true;
437 void Robot::readJoints()
440 std::vector<float> qi_joints_positions = memory_->getListData();
443 std::vector<double>::iterator hw_command_j = hw_commands_.begin();
444 std::vector<double>::iterator hw_angle_j = hw_angles_.begin();
445 std::vector<float>::iterator qi_position_j = qi_joints_positions.begin();
446 std::vector<bool>::iterator hw_enabled_j = hw_enabled_.begin();
448 for(; hw_command_j != hw_commands_.end(); ++hw_command_j, ++hw_angle_j, ++hw_enabled_j)
453 *hw_angle_j = *qi_position_j;
455 *hw_command_j = *qi_position_j;
462 void Robot::publishJointStateFromAlMotion(){
465 std::vector<double> position_data = motion_->getAngles(
"Body");
466 for(
int i = 0; i<position_data.size(); ++i)
467 joint_states_topic_.position[i] = position_data[i];
469 joint_states_pub_.publish(joint_states_topic_);
472 void Robot::writeJoints()
476 std::vector<double>::iterator hw_angle_j = hw_angles_.begin();
477 std::vector<double>::iterator hw_command_j = hw_commands_.begin();
478 std::vector<double>::iterator qi_command_j = qi_commands_.begin();
479 std::vector<bool>::iterator hw_enabled_j = hw_enabled_.begin();
480 for(
int i=0; hw_command_j != hw_commands_.end(); ++i, ++hw_command_j, ++hw_angle_j, ++hw_enabled_j)
485 *qi_command_j = *hw_command_j;
488 double diff = std::fabs(*hw_command_j - *hw_angle_j);
489 if(diff > joint_precision_)
501 dcm_->writeJoints(qi_commands_);
503 motion_->writeJoints(qi_commands_);
506 void Robot::ignoreMimicJoints(std::vector <std::string> *joints)
509 for(std::vector<std::string>::iterator it=joints->begin(); it!=joints->end(); ++it)
511 if( (it->find(
"Wheel") != std::string::npos)
512 || (*it==
"RHand" || *it==
"LHand" || *it ==
"RWristYaw" || *it ==
"LWristYaw") && (body_type_ ==
"H21"))
521 bool Robot::setStiffness(
const float &stiffness)
523 stiffness_.data = stiffness;
525 if (!motion_->stiffnessInterpolation(motor_groups_, stiffness, 2.0f))
This class is a wapper for Naoqi DCM Class.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
Type const & getType() const
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
static Quaternion createQuaternionFromYaw(double yaw)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
Motion(const qi::SessionPtr &session)
#define ROS_WARN_STREAM(args)
void writeJoints(const std::vector< double > &joint_commands)
set joints values
This class is a wapper for Naoqi Memory Class.
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void shutdown()
QI_REGISTER_OBJECT(Robot, isConnected, connect, stopService)
This class defines a Diagnostic It is used to check the robot state and sent to requesting nodes...