void Foam::BlockLduMatrix<Type>::Amul
(
    TypeField& Ax,
    const TypeField& x
) const
{
    Ax = pTraits<Type>::zero;

    // Initialise the update of coupled interfaces
    initInterfaces(coupleUpper_, Ax, x);

    AmulCore(Ax, x);

    // Update coupled interfaces
    updateInterfaces(coupleUpper_, Ax, x);
}
    bool init()
    {
        ROS_INFO_NAMED("init", "start");
        std::string param_name = "robot_description";
        std::string urdf_xml;

        if(!nodeHandle.getParam(param_name, urdf_xml) )
        {
            ROS_FATAL_NAMED(APPLICATION_NAME, "Could not load the parameter %s from param server\n", param_name.c_str());
            return false;
        }

//         std::cout << "\nurdf_xml before search id " << urdf_xml << std::endl;

        if(!robot_model.initString(urdf_xml) )
        {
            ROS_FATAL_NAMED(APPLICATION_NAME, "Could not load the 'robot_description' into a urdf::Model\n");
            return false;
        }

        std::cout << "****************************************" << std::endl;
        std::cout << "number of joints: " << robot_model.joints_.size() << std::endl;

        joint_num = 0;
        output_msg.names.clear();
        longestJointName_size = 0;
        std::pair<std::map<std::string, int>::iterator,bool> ret;

        for(std::map<std::string,boost::shared_ptr<urdf::Joint> >::iterator joint = robot_model.joints_.begin();  joint != robot_model.joints_.end(); joint++)
        {
            int jointType = joint->second.get()->type;
            if( (jointType != urdf::Joint::FIXED) && (jointType != urdf::Joint::UNKNOWN ))
            {
                ret = jointMap.insert(std::pair<std::string, int>(joint->first, joint_num) );
                if (ret.second==false)
                {
                    std::cout << "element " << joint->first <<  " already existed" << std::endl;
                }
                else
                    std::cout << "added element " << joint->first <<  " with value " << joint_num << std::endl;

                // set the name in the output message
//                 output_msg.names.push_back(joint->first);

                // increase the number of joints.
                joint_num++;
                if(joint->first.size() > longestJointName_size)
                    longestJointName_size = joint->first.size();
            }
        }

        std::cout << "number of joints NON FIXED: " << joint_num << std::endl;
        std::cout << "longestJointName_size: " << longestJointName_size << std::endl;
        std::cout << "****************************************" << std::endl;

        // assign will allocate the space, resize MUST not be done here
        measPos.assign(joint_num, 0);
        measVel.assign(joint_num, 0);
        measEff.assign(joint_num, 0);
        outCmd .assign(joint_num, 0);

        // Start the shared joint state subscriber
        jointState_subscriber = nodeHandle.subscribe<sensor_msgs::JointState>("/joint_states", 1,
                                                                              &MyRobot::stateCallback, this);

        // Start publishers
        std::string topicName;
        //     topicName = "/controller_cmd/joint_command";
        topicName = "/joint_states/cmd";
        yarpRosCmd_publisher = nodeHandle.advertise<robotology_msgs::controlBoardMsg>(topicName, 10);

        // name field will be allocated after using push_back
//         output_msg.reference.assign(joint_num, 0);
//         output_msg.referenceType.assign(joint_num, 0);

        ROS_INFO_NAMED("init", "end");

        initInterfaces();
        return true;
    }